how to use "SetAngularAccel"?
I wrote a very simple modelplugin. I just want to see how model moves when I use the method "SetAngularAccel" But, nothing happened,"SetAnfularAccel"doesn't work, my model still rests there. Please tell me what's wrong,Thank you!
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="test">
<link name="Link">
<self_collide>true</self_collide>
<pose>0 0 0.05 0 0 0</pose>
<inertial>
<mass> 0.1 </mass>
</inertial>
<collision name="Base_collision">
<geometry>
<box>
<size>0.1 2 0.1</size>
</box>
</geometry>
</collision>
<visual name="Visual">
<geometry>
<box>
<size>0.1 2 0.1</size>
</box>
</geometry>
</visual>
</link>
<plugin name="df" filename="/home/Dropbox/gazebo/torquetest/dist/Debug/GNU-Linux-x86/libtorquetest.so"/>
</model>
</sdf>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
using namespace gazebo;
class Arm_Control : public ModelPlugin
{
public:~Arm_Control(){}
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
{
this->model = _parent;
this->updateConnection = event::Events::ConnectWorldUpdateBegin(boost::bind(&Arm_Control::OnUpdate, this, _1));
}
public: void OnUpdate(const common::UpdateInfo & /*_info*/)
{
model->GetLink("Link")->SetAngularAccel(math::Vector3(0,0,1.5));
}
private:
physics::ModelPtr model;
event::ConnectionPtr updateConnection;
};
GZ_REGISTER_MODEL_PLUGIN(Arm_Control)
Asked by Zheng yo chen on 2014-06-24 02:22:16 UTC
Answers
None of our physics integration tests use SetAngularAccel, so it may not be working. Please create an issue and we will work on it. Thanks.
Asked by scpeters on 2014-06-25 19:44:12 UTC
Comments
Try adding larger values see if that works, test it if you are able to move it by adding a normal velocity to it, another problem might be that you didn't set the inertia matrix? Here's an example
https://bitbucket.org/osrf/gazebo/src/8b2d9259f8d0607f2cbeaf470e9349bbe4efa8c1/worlds/cart_demo.world?at=default#cl-29
and set the values to a small one, something like 0.001Asked by AndreiHaidu on 2014-06-24 07:46:21 UTC
Thank you your suggestion. ▇1.SetAngularVel() and SetLinearVel do work well ▇2.I set angular acceleration to 1000, my model still rests there[SetAngularAccel(math::Vector3(1000,1000,1000))] ▇3.I have added inertia matrix to my model sdf file,It still did not work [0.01 0 0 0.01 0 0.01 ]
Do you have any ideas? Thank you!
Asked by Zheng yo chen on 2014-06-25 00:28:56 UTC