Hello I want to change the mass property of a link in runtime. When i use the SetMass() function, Gazebo detect the change of mass value in the properties menu (the left one) but in the simulation the link continues behaving as if nothing had happened.
Should I use other function to update the values?
Thank you.
namespace gazebo
{
class joint_c : public ModelPlugin
{
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
{
this->model = _parent;
this->world= this->model->GetWorld();
this->mbox=this->world->GetModel("minibox");
this->jointR1_ = this->model->GetJoint("r1");
this->link1 = this->mbox->GetLink("link");
link1->GetInertial()->SetMass(800000); // Changing the mass
this->updateConnection = event::Events::ConnectWorldUpdateBegin(boost::bind(&joint_c::OnUpdate, this, _1));
}
public: void OnUpdate(const common::UpdateInfo &_info)
{
}
private:
physics::ModelPtr model;
physics::ModelPtr mbox;
physics::WorldPtr world;
event::ConnectionPtr updateConnection;
physics::JointPtr jointR1_;
physics::LinkPtr link1;
};
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(joint_c)
}
(re): I have tried to use the "virtual void UpdateParameters (sdf::ElementPtr _sdf)" function, but the console show me an error:
Error [Element.hh:360] Unable to find value for key[pose]
Error [Element.cc:684] Missing element description for [gravity]
My new lines of code are:
sdf::ElementPtr sdflink;
this->sdflink=this->link1->GetSDF();
this->sdflink->GetAttribute("name")->Set ("newName");
this->sdflink->GetElement("gravity")->Set(true);
this->sdflink->GetElement("pose")->Set(math::Pose(math::Vector3(-3, 0, 0), math::Quaternion(0, 0, 0)));
this->link1->UpdateParameters(sdflink);
What is going on?
↧