Skip to content

Commit

Permalink
fix(raw_vehicle_cmd_converter): remove external command converter val…
Browse files Browse the repository at this point in the history
…idation (autowarefoundation#2711)

* fix(raw_vehicle_cmd_converter): remove external command converter validation

Signed-off-by: taikitanaka3 <taiki.tanaka@tier4.jp>

* chore: fix

Signed-off-by: taikitanaka3 <taiki.tanaka@tier4.jp>
  • Loading branch information
taikitanaka3 authored and asana17 committed Feb 8, 2023
1 parent af82f1e commit 11da501
Show file tree
Hide file tree
Showing 8 changed files with 21 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace raw_vehicle_cmd_converter
class AccelMap
{
public:
bool readAccelMapFromCSV(const std::string & csv_path);
bool readAccelMapFromCSV(const std::string & csv_path, const bool validation = false);
bool getThrottle(const double acc, const double vel, double & throttle) const;
bool getAcceleration(const double throttle, const double vel, double & acc) const;
std::vector<double> getVelIdx() const { return vel_index_; }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace raw_vehicle_cmd_converter
class BrakeMap
{
public:
bool readBrakeMapFromCSV(const std::string & csv_path);
bool readBrakeMapFromCSV(const std::string & csv_path, const bool validation = false);
bool getBrake(const double acc, const double vel, double & brake);
bool getAcceleration(const double brake, const double vel, double & acc) const;
std::vector<double> getVelIdx() const { return vel_index_; }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace raw_vehicle_cmd_converter
class SteerMap
{
public:
bool readSteerMapFromCSV(const std::string & csv_path);
bool readSteerMapFromCSV(const std::string & csv_path, const bool validation = false);
void getSteer(const double steer_rate, const double steer, double & output) const;

private:
Expand Down
4 changes: 2 additions & 2 deletions vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ using namespace std::literals::chrono_literals;

namespace raw_vehicle_cmd_converter
{
bool AccelMap::readAccelMapFromCSV(const std::string & csv_path)
bool AccelMap::readAccelMapFromCSV(const std::string & csv_path, const bool validation)
{
CSVLoader csv(csv_path);
std::vector<std::vector<std::string>> table;
Expand All @@ -38,7 +38,7 @@ bool AccelMap::readAccelMapFromCSV(const std::string & csv_path)
vel_index_ = CSVLoader::getRowIndex(table);
throttle_index_ = CSVLoader::getColumnIndex(table);
accel_map_ = CSVLoader::getMap(table);
if (!CSVLoader::validateMap(accel_map_, true)) {
if (validation && !CSVLoader::validateMap(accel_map_, true)) {
return false;
}
return true;
Expand Down
4 changes: 2 additions & 2 deletions vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

namespace raw_vehicle_cmd_converter
{
bool BrakeMap::readBrakeMapFromCSV(const std::string & csv_path)
bool BrakeMap::readBrakeMapFromCSV(const std::string & csv_path, const bool validation)
{
CSVLoader csv(csv_path);
std::vector<std::vector<std::string>> table;
Expand All @@ -36,7 +36,7 @@ bool BrakeMap::readBrakeMapFromCSV(const std::string & csv_path)
brake_index_ = CSVLoader::getColumnIndex(table);
brake_map_ = CSVLoader::getMap(table);
brake_index_rev_ = brake_index_;
if (!CSVLoader::validateMap(brake_map_, false)) {
if (validation && !CSVLoader::validateMap(brake_map_, false)) {
return false;
}
std::reverse(std::begin(brake_index_rev_), std::end(brake_index_rev_));
Expand Down
6 changes: 3 additions & 3 deletions vehicle/raw_vehicle_cmd_converter/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,17 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
use_steer_ff_ = declare_parameter("use_steer_ff", true);
use_steer_fb_ = declare_parameter("use_steer_fb", true);
if (convert_accel_cmd_) {
if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map)) {
if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map, true)) {
throw std::invalid_argument("Accel map is invalid.");
}
}
if (convert_brake_cmd_) {
if (!brake_map_.readBrakeMapFromCSV(csv_path_brake_map)) {
if (!brake_map_.readBrakeMapFromCSV(csv_path_brake_map, true)) {
throw std::invalid_argument("Brake map is invalid.");
}
}
if (convert_steer_cmd_) {
if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map)) {
if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map, true)) {
throw std::invalid_argument("Steer map is invalid.");
}
const auto kp_steer{declare_parameter("steer_pid.kp", 150.0)};
Expand Down
4 changes: 2 additions & 2 deletions vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
namespace raw_vehicle_cmd_converter
{

bool SteerMap::readSteerMapFromCSV(const std::string & csv_path)
bool SteerMap::readSteerMapFromCSV(const std::string & csv_path, const bool validation)
{
CSVLoader csv(csv_path);
std::vector<std::vector<std::string>> table;
Expand All @@ -35,7 +35,7 @@ bool SteerMap::readSteerMapFromCSV(const std::string & csv_path)
steer_index_ = CSVLoader::getRowIndex(table);
output_index_ = CSVLoader::getColumnIndex(table);
steer_map_ = CSVLoader::getMap(table);
if (!CSVLoader::validateMap(steer_map_, true)) {
if (validation && !CSVLoader::validateMap(steer_map_, true)) {
return false;
}
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ TEST(ConverterTests, LoadExampleMap)
const auto data_path =
ament_index_cpp::get_package_share_directory("raw_vehicle_cmd_converter") + "/data/default/";
// for invalid path
EXPECT_TRUE(accel_map.readAccelMapFromCSV(data_path + "accel_map.csv"));
EXPECT_TRUE(brake_map.readBrakeMapFromCSV(data_path + "brake_map.csv"));
EXPECT_TRUE(steer_map.readSteerMapFromCSV(data_path + "steer_map.csv"));
EXPECT_TRUE(accel_map.readAccelMapFromCSV(data_path + "accel_map.csv", true));
EXPECT_TRUE(brake_map.readBrakeMapFromCSV(data_path + "brake_map.csv", true));
EXPECT_TRUE(steer_map.readSteerMapFromCSV(data_path + "steer_map.csv", true));
}

TEST(ConverterTests, LoadValidPath)
Expand All @@ -112,14 +112,14 @@ TEST(ConverterTests, LoadValidPath)
EXPECT_TRUE(loadSteerMapData(steer_map));

// for invalid path
EXPECT_FALSE(accel_map.readAccelMapFromCSV("invalid.csv"));
EXPECT_FALSE(brake_map.readBrakeMapFromCSV("invalid.csv"));
EXPECT_FALSE(steer_map.readSteerMapFromCSV("invalid.csv"));
EXPECT_FALSE(accel_map.readAccelMapFromCSV("invalid.csv", true));
EXPECT_FALSE(brake_map.readBrakeMapFromCSV("invalid.csv", true));
EXPECT_FALSE(steer_map.readSteerMapFromCSV("invalid.csv", true));

// for invalid maps
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_1col_map.csv"));
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_inconsistent_rows_map.csv"));
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_not_interpolatable.csv"));
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_1col_map.csv", true));
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_inconsistent_rows_map.csv", true));
EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_not_interpolatable.csv", true));
}

TEST(ConverterTests, AccelMapCalculation)
Expand Down

0 comments on commit 11da501

Please sign in to comment.