Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

JointGroupPositionController: Set current position as target in starting() #504

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ class JointGroupPositionController : public controller_interface::Controller<har

bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n);
void update(const ros::Time& /*time*/, const ros::Duration& /*period*/);
void starting(const ros::Time& /*time*/);

std::vector< std::string > joint_names_;
std::vector< hardware_interface::JointHandle > joints_;
Expand Down
14 changes: 13 additions & 1 deletion effort_controllers/src/joint_group_position_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,14 +120,26 @@ namespace effort_controllers
return true;
}

void JointGroupPositionController::starting(const ros::Time& time)
{
std::vector<double> current_positions(n_joints_, 0.0);
for (std::size_t i = 0; i < n_joints_; ++i)
{
current_positions[i] = joints_[i].getPosition();
enforceJointLimits(current_positions[i], i);
pid_controllers_[i].reset();
}
commands_buffer_.initRT(current_positions);
}

void JointGroupPositionController::update(const ros::Time& time, const ros::Duration& period)
{
std::vector<double> & commands = *commands_buffer_.readFromRT();
for(unsigned int i=0; i<n_joints_; i++)
{
double command_position = commands[i];

double error; //, vel_error;
double error;
double commanded_effort;

double current_position = joints_[i].getPosition();
Expand Down