Skip to content

Fix uninitialized acceleration limit, and add unit tests to TricycleDrive plugin#84

Merged
josephduchesne merged 6 commits intomasterfrom
fix-uninitialized-acceleration-limit
Jan 17, 2023
Merged

Fix uninitialized acceleration limit, and add unit tests to TricycleDrive plugin#84
josephduchesne merged 6 commits intomasterfrom
fix-uninitialized-acceleration-limit

Conversation

@josephduchesne
Copy link
Copy Markdown
Collaborator

No description provided.

ros::spinOnce();
}

// TODO: Check odom is 0 linear, 0 angular
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Does this TODO still apply?


// directly set the Twist message for velocity input
geometry_msgs::Twist cmd_vel;
cmd_vel.angular.x = 0; //m/s
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Should this be linear.x = 0?



// rotate front wheel for 1 seconds
cmd_vel.angular.z = 0.5; // rad/s, but the limit is 0.2m/s
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

// rad/s, but the limit is 0.2 rad/s

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Just this one comment (the units at the end should be rad/s) otherwise PR looks good

}
EXPECT_NEAR(0.2, odom.twist.twist.linear.x, 0.01); // verify that we're being capped at 0.2m/s
EXPECT_NEAR(0, odom.twist.twist.angular.z, 0.01);
EXPECT_NEAR(12.2, odom.pose.pose.position.x, 0.01); // should have driven 0.5m from the start
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

// should have driven 0.2 m


EXPECT_NEAR(0.0, odom.twist.twist.linear.x, 0.01);
EXPECT_NEAR(0, odom.twist.twist.angular.z, 0.01);
EXPECT_NEAR(12.2, odom.pose.pose.position.x, 0.01); // should have driven 0.5m from the start
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

// should have driven 0.2 m

ros::spinOnce();
}

// TODO: Check odom is 0 linear, 0 angular
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Remove TODO

ros::spinOnce();
}

// TODO: Check odom is 0 linear, 0 angular
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Remove TODO

// front wheel should have rotated to 0.2 radians, but we didn't move
EXPECT_NEAR(0.0, odom.twist.twist.linear.x, 0.01);
EXPECT_NEAR(0.0, odom.twist.twist.angular.z, 0.01);
EXPECT_NEAR(12.0, odom.pose.pose.position.x, 0.01); // should have driven 0.5m from the start
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

// should not have moved from the start

@josephduchesne josephduchesne merged commit d4b1cfb into master Jan 17, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants