Skip to content

Commit

Permalink
Changed the function namings by camelCase and some changes in launch …
Browse files Browse the repository at this point in the history
…files
  • Loading branch information
CihatAltiparmak committed Jun 10, 2024
1 parent bfbfc0d commit 1d3f0ff
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 22 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/industrial_ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@ jobs:
ROS_DISTRO: [iron]
ROS_REPO: [testing, main]
env:
CCACHE_DIR: "${{ github.workspace }}/.ccache"
CCACHE_DIR: "${{ github.workspace }}/.ccache"
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: 'ros-industrial/industrial_ci@master'
env: # either pass all entries explicitly
ROS_DISTRO: ${{ matrix.ROS_DISTRO }}
ROS_REPO: ${{ matrix.ROS_REPO }}
ROS_REPO: ${{ matrix.ROS_REPO }}
Original file line number Diff line number Diff line change
Expand Up @@ -199,10 +199,10 @@ def generate_launch_description():
mongodb_server_node,
# for https://github.com/ros-controls/ros2_controllers/issues/981
RegisterEventHandler(
OnProcessStart(
OnProcessExit(
target_action=panda_arm_controller_spawner,
on_start=[
LogInfo(msg="Started panda_arm_controller_spawner"),
on_exit=[
LogInfo(msg="panda_arm_controller_spawner is finished. Now test_scenario_perception_pipeline will start"),
test_scenario_perception_pipeline_node,
],
)
Expand Down
31 changes: 14 additions & 17 deletions test/test_scenario_perception_pipeline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,12 @@

using moveit::planning_interface::MoveGroupInterface;

// class MoveGroupServer {
// };

class ScenarioPerceptionPipeline
{
public:
ScenarioPerceptionPipeline(std::shared_ptr<MoveGroupInterface>);
std::tuple<int, int> run_test_case(std::vector<geometry_msgs::msg::Pose> pose_list);
bool send_target_pose(geometry_msgs::msg::Pose target_pose);
std::tuple<int, int> runTestCase(const std::vector<geometry_msgs::msg::Pose>& pose_list);
bool sendTargetPose(const geometry_msgs::msg::Pose& target_pose);

private:
std::shared_ptr<MoveGroupInterface> move_group_interface_ptr_;
Expand All @@ -29,13 +26,13 @@ ScenarioPerceptionPipeline::ScenarioPerceptionPipeline(std::shared_ptr<MoveGroup
{
}

std::tuple<int, int> ScenarioPerceptionPipeline::run_test_case(std::vector<geometry_msgs::msg::Pose> test_case)
std::tuple<int, int> ScenarioPerceptionPipeline::runTestCase(const std::vector<geometry_msgs::msg::Pose>& test_case)
{
int success_number = 0;
int failure_number = 0;
for (auto& pose : test_case)
{
bool is_successful = send_target_pose(pose);
bool is_successful = sendTargetPose(pose);
if (is_successful)
success_number++;
else
Expand All @@ -45,7 +42,7 @@ std::tuple<int, int> ScenarioPerceptionPipeline::run_test_case(std::vector<geome
return { success_number, failure_number };
}

bool ScenarioPerceptionPipeline::send_target_pose(geometry_msgs::msg::Pose target_pose)
bool ScenarioPerceptionPipeline::sendTargetPose(const geometry_msgs::msg::Pose& target_pose)
{
move_group_interface_ptr_->setPoseTarget(target_pose);

Expand All @@ -69,20 +66,20 @@ class ScenarioPerceptionPipelineTestCaseCreator
static inline std::vector<std::vector<geometry_msgs::msg::Pose>> test_cases_ = {};

public:
static void create_test_cases()
static void createTestCases()
{
std::vector<geometry_msgs::msg::Pose> example_pose_list_;

geometry_msgs::msg::Pose target_pose1_msg;
target_pose1_msg.orientation.w = 1.0;
target_pose1_msg.position.x = -0.7;
target_pose1_msg.position.y = 0.0;
target_pose1_msg.position.x = 0.5;
target_pose1_msg.position.y = 0.5;
target_pose1_msg.position.z = 0.5;

geometry_msgs::msg::Pose target_pose2_msg;
target_pose2_msg.orientation.w = 1.0;
target_pose2_msg.position.x = 0.4;
target_pose2_msg.position.y = 0.0;
target_pose2_msg.position.x = 0.5;
target_pose2_msg.position.y = -0.5;
target_pose2_msg.position.z = 0.7;

for (int i = 0; i < 10; i++)
Expand All @@ -94,7 +91,7 @@ class ScenarioPerceptionPipelineTestCaseCreator
test_cases_.push_back(example_pose_list_);
}

static std::vector<geometry_msgs::msg::Pose> select_test_case(size_t test_case_index)
static std::vector<geometry_msgs::msg::Pose> selectTestCases(size_t test_case_index)
{
return test_cases_.at(test_case_index);
}
Expand All @@ -111,7 +108,7 @@ class ScenarioPerceptionPipelineFixture : public benchmark::Fixture
ScenarioPerceptionPipelineFixture()
{
PLANNING_GROUP = "panda_arm";
ScenarioPerceptionPipelineTestCaseCreator::create_test_cases();
ScenarioPerceptionPipelineTestCaseCreator::createTestCases();
}

void SetUp(::benchmark::State& /*state*/)
Expand All @@ -136,11 +133,11 @@ class ScenarioPerceptionPipelineFixture : public benchmark::Fixture

BENCHMARK_DEFINE_F(ScenarioPerceptionPipelineFixture, test_scenario_perception_pipeline)(benchmark::State& st)
{
auto selected_test_case = ScenarioPerceptionPipelineTestCaseCreator::select_test_case(0);
auto selected_test_case = ScenarioPerceptionPipelineTestCaseCreator::selectTestCases(0);
for (auto _ : st)
{
auto sc = ScenarioPerceptionPipeline(move_group_interface_ptr_);
sc.run_test_case(selected_test_case);
sc.runTestCase(selected_test_case);
}
}

Expand Down

0 comments on commit 1d3f0ff

Please sign in to comment.