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

Add option to wait convergence of joint trajectory angle and velocity #122

Merged
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
7 changes: 6 additions & 1 deletion src/ypspur_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,7 @@ class YpspurRosNode
std::map<std::string, double> params_;
int key_;
bool simulate_;
bool wait_convergence_of_joint_trajectory_angle_vel_;

double tf_time_offset_;

Expand Down Expand Up @@ -451,6 +452,8 @@ class YpspurRosNode
ROS_WARN("simulate_control parameter is deprecated. Use simulate parameter instead");
simulate_ = true;
}
pnh_.param(
"wait_convergence_of_joint_trajectory_angle_vel", wait_convergence_of_joint_trajectory_angle_vel_, true);
pnh_.param("ypspur_bin", ypspur_bin_, std::string("ypspur-coordinator"));
pnh_.param("param_file", param_file_, std::string(""));
pnh_.param("tf_time_offset", tf_time_offset_, 0.0);
Expand Down Expand Up @@ -1099,7 +1102,8 @@ class YpspurRosNode

if (done)
{
if ((joints_[jid].vel_end_ > 0.0 &&
if (!wait_convergence_of_joint_trajectory_angle_vel_ ||
(joints_[jid].vel_end_ > 0.0 &&
joints_[jid].angle_ref_ > joint.position[jid] &&
joints_[jid].angle_ref_ < joint.position[jid] + joints_[jid].vel_ref_ * dt) ||
(joints_[jid].vel_end_ < 0.0 &&
Expand All @@ -1108,6 +1112,7 @@ class YpspurRosNode
{
joints_[jid].control_ = JointParams::VELOCITY;
joints_[jid].vel_ref_ = joints_[jid].vel_end_;
YP::YP_joint_vel(joints_[jid].id_, joints_[jid].vel_ref_);
}
}
}
Expand Down
26 changes: 26 additions & 0 deletions test/src/joint_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,32 @@ TEST(JointTrajectory, CommandValidation)
}
ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
<< "Outdated joint_trajectory must be ignored";

// Publish overshoot command
cmd.header.stamp = ros::Time::now();
cmd.joint_names.resize(1);
cmd.joint_names[0] = "joint0";
cmd.points.resize(1);
cmd.points[0].time_from_start = ros::Duration(1);
cmd.points[0].positions.resize(1);
cmd.points[0].positions[0] = 1.0;
cmd.points[0].velocities.resize(1);
cmd.points[0].velocities[0] = 4.0;
pub_cmd.publish(cmd);
wait.sleep();

for (int i = 0; i < 50; ++i)
{
wait.sleep();
ros::spinOnce();
}

ASSERT_TRUE(static_cast<bool>(joint_states));
ASSERT_EQ(joint_states->name.size(), 1u);
ASSERT_EQ(joint_states->name[0], "joint0");
ASSERT_EQ(joint_states->velocity.size(), 1u);
ASSERT_NEAR(joint_states->velocity[0], 4.0, 0.1)
<< "Joint velocity should be near the target value";
}

int main(int argc, char** argv)
Expand Down
1 change: 1 addition & 0 deletions test/test/joint_trajectory.test
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,6 @@
<param name="param_file" value="$(find ypspur_ros)/test/config/test.param" />
<param name="joint0_enable" value="true" />
<param name="hz" value="20.0" />
<param name="wait_convergence_of_joint_trajectory_angle_vel" value="false" />
</node>
</launch>
Loading