Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions hebiros_gazebo_plugin/include/hebiros_gazebo_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -366,9 +366,9 @@ double HebirosGazeboController::ComputeForce(std::shared_ptr<HebirosGazeboGroup>
hebiros_joint->temperature.update(power_in, iteration_time.toSec());
hebiros_joint->temperature_safety.update(hebiros_joint->temperature.getMotorWindingTemperature());

//alpha = hebiros_joint->low_pass_alpha;
//force = (force * alpha) + hebiros_joint->prev_force * (1 - alpha);
//hebiros_joint->prev_force = force;
alpha = hebiros_joint->low_pass_alpha;
force = (force * alpha) + hebiros_joint->prev_force * (1 - alpha);
hebiros_joint->prev_force = force;

return force;
}
Expand Down
3 changes: 3 additions & 0 deletions hebiros_gazebo_plugin/include/hebiros_gazebo_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@ class HebirosGazeboPlugin: public ModelPlugin {
void AddJointToGroup(std::shared_ptr<HebirosGazeboGroup> hebiros_group, std::string joint_name);
void UpdateGroup(std::shared_ptr<HebirosGazeboGroup> hebiros_group, const ros::Duration& iteration_time);

double prev_effort;
double low_pass_alpha;

bool SrvAddGroup(AddGroupFromNamesSrv::Request &req,
AddGroupFromNamesSrv::Response &res);

Expand Down
14 changes: 11 additions & 3 deletions hebiros_gazebo_plugin/plugin/hebiros_gazebo_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@ void HebirosGazeboPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) {
this->update_connection = event::Events::ConnectWorldUpdateBegin (
boost::bind(&HebirosGazeboPlugin::OnUpdate, this, _1));

this->prev_effort = 0.0;
this->low_pass_alpha = 0.1;

ROS_INFO("Loaded hebiros gazebo plugin");
}

Expand Down Expand Up @@ -68,9 +71,14 @@ void HebirosGazeboPlugin::UpdateGroup(std::shared_ptr<HebirosGazeboGroup> hebiro
joint->SetProvideFeedback(true);
double position = joint->GetAngle(0).Radian();
double velocity = joint->GetVelocity(0);
physics::JointWrench wrench = joint->GetForceTorque(0);
auto trans = joint->GetChild()->GetInitialRelativePose().rot;
double effort = (-1 * (trans * wrench.body1Torque)).z;
//physics::JointWrench wrench = joint->GetForceTorque(0u); // Net torque (motor + environment). Non-zero values represent transient effects.
//double effort = -1*wrench.body2Torque.z; // reactive torque from motor
//effort = std::max(-20.0, std::min(20.0, effort));
//effort += joint->GetForce(0); // torque from motor
double effort = joint->GetForce(0);
double alpha = this->low_pass_alpha;
effort = (effort * alpha) + this->prev_effort * (1 - alpha);
this->prev_effort = effort;

hebiros_group->feedback.position[i] = position;
hebiros_group->feedback.velocity[i] = velocity;
Expand Down