@@ -43,32 +43,32 @@ namespace bind_planning_interface
43
43
std::shared_ptr<robot_trajectory::RobotTrajectory>
44
44
get_motion_plan_response_trajectory (std::shared_ptr<planning_interface::MotionPlanResponse>& response)
45
45
{
46
- return response->trajectory_ ;
46
+ return response->trajectory ;
47
47
}
48
48
49
49
moveit_msgs::msg::RobotState
50
50
get_motion_plan_response_start_state (std::shared_ptr<planning_interface::MotionPlanResponse>& response)
51
51
{
52
- moveit_msgs::msg::RobotState robot_state_msg = response->start_state_ ;
52
+ moveit_msgs::msg::RobotState robot_state_msg = response->start_state ;
53
53
return robot_state_msg;
54
54
}
55
55
56
56
moveit_msgs::msg::MoveItErrorCodes
57
57
get_motion_plan_response_error_code (std::shared_ptr<planning_interface::MotionPlanResponse>& response)
58
58
{
59
59
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 );
61
61
return error_code_msg;
62
62
}
63
63
64
64
double get_motion_plan_response_planning_time (std::shared_ptr<planning_interface::MotionPlanResponse>& response)
65
65
{
66
- return response->planning_time_ ;
66
+ return response->planning_time ;
67
67
}
68
68
69
69
std::string get_motion_plan_response_planner_id (std::shared_ptr<planning_interface::MotionPlanResponse>& response)
70
70
{
71
- return response->planner_id_ ;
71
+ return response->planner_id ;
72
72
}
73
73
74
74
void init_motion_plan_response (py::module& m)
@@ -83,7 +83,7 @@ void init_motion_plan_response(py::module& m)
83
83
.def_property (" trajectory" , &moveit_py::bind_planning_interface::get_motion_plan_response_trajectory, nullptr ,
84
84
py::return_value_policy::copy, R"( )" )
85
85
86
- .def_readonly (" planning_time" , &planning_interface::MotionPlanResponse::planning_time_ ,
86
+ .def_readonly (" planning_time" , &planning_interface::MotionPlanResponse::planning_time ,
87
87
py::return_value_policy::copy, R"( )" )
88
88
89
89
.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)
92
92
.def_property (" start_state" , &moveit_py::bind_planning_interface::get_motion_plan_response_start_state, nullptr ,
93
93
py::return_value_policy::copy, R"( )" )
94
94
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,
96
96
R"( )" )
97
97
98
98
.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;
100
100
});
101
101
}
102
102
} // namespace bind_planning_interface
0 commit comments