Skip to content

Commit d9fdbf6

Browse files
remove underscore from public members in MotionPlanResponse
Completed to align with 8bfe782
1 parent b638ce7 commit d9fdbf6

File tree

1 file changed

+8
-8
lines changed

1 file changed

+8
-8
lines changed

moveit_py/src/moveit/moveit_core/planning_interface/planning_response.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -43,32 +43,32 @@ namespace bind_planning_interface
4343
std::shared_ptr<robot_trajectory::RobotTrajectory>
4444
get_motion_plan_response_trajectory(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
4545
{
46-
return response->trajectory_;
46+
return response->trajectory;
4747
}
4848

4949
moveit_msgs::msg::RobotState
5050
get_motion_plan_response_start_state(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
5151
{
52-
moveit_msgs::msg::RobotState robot_state_msg = response->start_state_;
52+
moveit_msgs::msg::RobotState robot_state_msg = response->start_state;
5353
return robot_state_msg;
5454
}
5555

5656
moveit_msgs::msg::MoveItErrorCodes
5757
get_motion_plan_response_error_code(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
5858
{
5959
moveit_msgs::msg::MoveItErrorCodes error_code_msg =
60-
static_cast<moveit_msgs::msg::MoveItErrorCodes>(response->error_code_);
60+
static_cast<moveit_msgs::msg::MoveItErrorCodes>(response->error_code);
6161
return error_code_msg;
6262
}
6363

6464
double get_motion_plan_response_planning_time(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
6565
{
66-
return response->planning_time_;
66+
return response->planning_time;
6767
}
6868

6969
std::string get_motion_plan_response_planner_id(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
7070
{
71-
return response->planner_id_;
71+
return response->planner_id;
7272
}
7373

7474
void init_motion_plan_response(py::module& m)
@@ -83,7 +83,7 @@ void init_motion_plan_response(py::module& m)
8383
.def_property("trajectory", &moveit_py::bind_planning_interface::get_motion_plan_response_trajectory, nullptr,
8484
py::return_value_policy::copy, R"()")
8585

86-
.def_readonly("planning_time", &planning_interface::MotionPlanResponse::planning_time_,
86+
.def_readonly("planning_time", &planning_interface::MotionPlanResponse::planning_time,
8787
py::return_value_policy::copy, R"()")
8888

8989
.def_property("error_code", &moveit_py::bind_planning_interface::get_motion_plan_response_error_code, nullptr,
@@ -92,11 +92,11 @@ void init_motion_plan_response(py::module& m)
9292
.def_property("start_state", &moveit_py::bind_planning_interface::get_motion_plan_response_start_state, nullptr,
9393
py::return_value_policy::copy, R"()")
9494

95-
.def_readonly("planner_id", &planning_interface::MotionPlanResponse::planner_id_, py::return_value_policy::copy,
95+
.def_readonly("planner_id", &planning_interface::MotionPlanResponse::planner_id, py::return_value_policy::copy,
9696
R"()")
9797

9898
.def("__bool__", [](std::shared_ptr<planning_interface::MotionPlanResponse>& response) {
99-
return response->error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
99+
return response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
100100
});
101101
}
102102
} // namespace bind_planning_interface

0 commit comments

Comments
 (0)