Skip to content

Commit

Permalink
Fix failing tests
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 18, 2024
1 parent 33ab27a commit 9e35eca
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -273,20 +273,19 @@ class AckermannSteeringControllerFixture : public ::testing::Test
bool open_loop_ = false;
unsigned int velocity_rolling_window_size_ = 10;
bool position_feedback_ = false;
std::vector<std::string> rear_wheels_names_ = {
{"rear_right_wheel_joint", "rear_left_wheel_joint"}};
std::vector<std::string> rear_wheels_names_ = {"rear_right_wheel_joint", "rear_left_wheel_joint"};
std::vector<std::string> front_wheels_names_ = {
{"front_right_steering_joint", "front_left_steering_joint"}};
"front_right_steering_joint", "front_left_steering_joint"};
std::vector<std::string> joint_names_ = {
{rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]}};
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]};

std::vector<std::string> rear_wheels_preceeding_names_ = {
{"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"}};
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_ = {
{"pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"}};
"pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"};
std::vector<std::string> preceeding_joint_names_ = {
{rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]}};
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]};

double wheelbase_ = 3.24644;
double front_wheel_track_ = 2.12321;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -260,30 +260,27 @@ class TricycleSteeringControllerFixture : public ::testing::Test
bool open_loop_ = false;
unsigned int velocity_rolling_window_size_ = 10;
bool position_feedback_ = false;
std::vector<std::string> rear_wheels_names_ = {
{"rear_right_wheel_joint", "rear_left_wheel_joint"}};
std::vector<std::string> front_wheels_names_ = {{"steering_axis_joint"}};
std::vector<std::string> joint_names_ = {
{rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0]}};

std::vector<std::string> rear_wheels_preceeding_names_ = {
{"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"}};
std::vector<std::string> front_wheels_preceeding_names_ = {
{"pid_controller/steering_axis_joint"}};
std::vector<std::string> preceeding_joint_names_ = {
{rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0]}};
std::vector<std::string> rear_wheels_names_{"rear_right_wheel_joint", "rear_left_wheel_joint"};
std::vector<std::string> front_wheels_names_{"steering_axis_joint"};
std::vector<std::string> joint_names_{
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0]};

std::vector<std::string> rear_wheels_preceeding_names_{
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_{"pid_controller/steering_axis_joint"};
std::vector<std::string> preceeding_joint_names_{
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0]};

double wheelbase_ = 3.24644;
double wheel_track_ = 1.212121;

double front_wheels_radius_ = 0.45;
double rear_wheels_radius_ = 0.45;

std::array<double, 3> joint_state_values_ = {{0.5, 0.5, 0.0}};
std::array<double, 3> joint_command_values_ = {{1.1, 3.3, 2.2}};
std::array<std::string, 2> joint_reference_interfaces_ = {
{"linear/velocity", "angular/velocity"}};
std::array<double, 3> joint_state_values_{{0.5, 0.5, 0.0}};
std::array<double, 3> joint_command_values_{{1.1, 3.3, 2.2}};
std::array<std::string, 2> joint_reference_interfaces_{{"linear/velocity", "angular/velocity"}};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down

0 comments on commit 9e35eca

Please sign in to comment.