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

Change double comparison to use epsilon instead of 0.0 #236

Closed
wants to merge 1 commit into from
Closed
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
2 changes: 1 addition & 1 deletion src/ActionServer_FJT.c
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ void Ros_ActionServer_FJT_Goal_Complete(GOAL_END_TYPE goal_end_type)
diff = fabs(feedback_FollowJointTrajectory.feedback.desired.positions.data[axis] - feedback_FollowJointTrajectory.feedback.actual.positions.data[axis]);

double posTolerance = g_actionServer_FJT_SendGoal_Request.goal.goal_tolerance.data[axis].position; //user-provided a goal_tolerance
Copy link
Collaborator

@gavanderhoorn gavanderhoorn Apr 12, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should we not check whether g_actionServer_FJT_SendGoal_Request.goal.goal_tolerance.data is of the expected/required size? Otherwise we could be trying to read outside the array.

We might already be doing that before we get here, I haven't checked.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We might already be doing that before we get here, I haven't checked

We're not.

You're correct in that this is another potential issue.

@yai-rosejo mentioned in passing that he's got a branch doing some more thorough checking. I'll let him comment on what he's done.

if (posTolerance == 0.0) //user did NOT provide a tolerance
if (fabs(posTolerance) < EPSILON_TOLERANCE_DOUBLE) //user did NOT provide a tolerance (posTolerance == 0.0)
posTolerance = DEFAULT_FJT_GOAL_POSITION_TOLERANCE;

if (diff > posTolerance)
Expand Down
Loading