Skip to content
Snippets Groups Projects
Commit c750eb2d authored by Tommy Persson's avatar Tommy Persson
Browse files

Fixe.

parent 63b6dbf6
No related branches found
No related tags found
No related merge requests found
......@@ -18,8 +18,12 @@ find_package(nav2_common REQUIRED)
find_package(nav2_util REQUIRED)
# SIP/Python stuff
find_package(PythonInterp 3.0 REQUIRED)
find_package(PythonLibrary 3.0 REQUIRED)
#find_package(PythonInterp 3.0 REQUIRED)
#find_package(PythonLibrary 3.0 REQUIRED)
#find_package(SIP 4.18.0 REQUIRED)
find_package(PythonInterp 3.10 REQUIRED)
find_package(PythonLibrary 3.10 REQUIRED)
find_package(SIP 4.18.0 REQUIRED)
nav2_package()
......@@ -36,7 +40,10 @@ set(dependencies
pluginlib
nav2_util
nav2_costmap_2d
)
)
message("LIBS: ${PYTHON_LIBRARY}")
message("DEPS: ${dependencies}")
add_library(air_navigation SHARED
src/python_controller.cpp
......@@ -44,7 +51,7 @@ add_library(air_navigation SHARED
src/python_trajectory_critic.cpp
src/python_trajectory_generator.cpp)
target_compile_definitions(air_navigation PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
target_link_libraries(air_navigation ${PYTHON_LIBRARY} )
target_link_libraries(air_navigation ${PYTHON_LIBRARY})
target_include_directories(air_navigation
PUBLIC
/opt/ros/humble/include/nav_2d_msgs
......
......@@ -19,7 +19,7 @@ void PythonController::configure(
std::shared_ptr<nav2_costmap_2d::Costmap2DROS>)
{
auto node = parent.lock();
RCLCPP_ERROR_STREAM(node->get_logger(), "Configuring Python controller");
RCLCPP_ERROR_STREAM(node->get_logger(), "****************** Configuring Python controller");
nav2_util::declare_parameter_if_not_declared(node, name + ".module", rclcpp::ParameterValue(""));
nav2_util::declare_parameter_if_not_declared(node, name + ".class", rclcpp::ParameterValue(""));
......@@ -65,6 +65,7 @@ geometry_msgs::msg::TwistStamped PythonController::computeVelocityCommands(
nav2_core::GoalChecker * goal)
{
python_lock pl;
if(m_python_controller_interface)
{
py_interface::PoseStamped py_pose;
......@@ -86,6 +87,7 @@ geometry_msgs::msg::TwistStamped PythonController::computeVelocityCommands(
void PythonController::setPlan(const nav_msgs::msg::Path & path)
{
python_lock pl;
if(m_python_controller_interface)
{
py_interface::Path py_path;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment