Skip to content

Commit

Permalink
use float msg for debugging from example_interfaces
Browse files Browse the repository at this point in the history
std_msgs float got removed after foxy
  • Loading branch information
Cakem1x committed Jan 25, 2024
1 parent 4ecd8be commit d634307
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 6 deletions.
6 changes: 4 additions & 2 deletions mesh_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,23 @@ cmake_minimum_required(VERSION 3.8)
project(mesh_controller)

find_package(ament_cmake_ros REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(mbf_mesh_core REQUIRED)
find_package(mbf_msgs REQUIRED)
find_package(mbf_utility REQUIRED)
find_package(mesh_map REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)


pluginlib_export_plugin_description_file(mbf_mesh_core mesh_controller.xml)

add_library(${PROJECT_NAME} src/mesh_controller.cpp)
target_include_directories(${PROJECT_NAME} PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_compile_definitions(${PROJECT_NAME} PRIVATE "MESH_CONTROLLER_BUILDING_LIBRARY")
ament_target_dependencies(${PROJECT_NAME} mbf_mesh_core mbf_msgs mbf_utility mesh_map rclcpp tf2_geometry_msgs)
ament_target_dependencies(${PROJECT_NAME} example_interfaces mbf_mesh_core mbf_msgs mbf_utility mesh_map rclcpp tf2_geometry_msgs)

install(DIRECTORY include DESTINATION include)
install(TARGETS ${PROJECT_NAME}
Expand All @@ -29,5 +31,5 @@ install(TARGETS ${PROJECT_NAME}
ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_export_targets(export_${PROJECT_NAME})
ament_export_dependencies(mbf_mesh_core mbf_msgs mbf_utility mesh_map rclcpp tf2_geometry_msgs)
ament_export_dependencies(example_interfaces mbf_mesh_core mbf_msgs mbf_utility mesh_map rclcpp tf2_geometry_msgs)
ament_package()
3 changes: 2 additions & 1 deletion mesh_controller/include/mesh_controller/mesh_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@

#include <mbf_mesh_core/mesh_controller.h>
#include <mbf_msgs/action/get_path.hpp>
#include <example_interfaces/msg/float32.hpp>
#include <mesh_map/mesh_map.h>
#include <visualization_msgs/msg/marker_array.hpp>

Expand Down Expand Up @@ -180,7 +181,7 @@ class MeshController : public mbf_mesh_core::MeshController
lvr2::DenseVertexMap<mesh_map::Vector> vector_map_;

//! publishes the angle between the robots orientation and the goal vector field for debug purposes
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr angle_pub_;
rclcpp::Publisher<example_interfaces::msg::Float32>::SharedPtr angle_pub_;

//! flag to handle cancel requests
std::atomic_bool cancel_requested_;
Expand Down
1 change: 1 addition & 0 deletions mesh_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>mesh_map</depend>
<depend>rclcpp</depend>
<depend>tf2_geometry_msgs</depend>
<depend>example_interfaces</depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
5 changes: 2 additions & 3 deletions mesh_controller/src/mesh_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
#include <mesh_controller/mesh_controller.h>
#include <mesh_map/util.h>
#include <pluginlib/class_list_macros.hpp>
#include <std_msgs/msg/float32.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <mbf_utility/exe_path_exception.h>

Expand Down Expand Up @@ -229,7 +228,7 @@ std::array<float, 2> MeshController::naiveControl(
float phi = acos(mesh_dir.dot(robot_dir));
float sign_phi = mesh_dir.cross(robot_dir).dot(mesh_normal);
// debug output angle between supposed and current angle
DEBUG_CALL(std_msgs::msg::Float32 angle32; angle32.data = phi * 180 / M_PI; angle_pub_->publish(angle32);)
DEBUG_CALL(example_interfaces::msg::Float32 angle32; angle32.data = phi * 180 / M_PI; angle_pub_->publish(angle32);)

float angular_velocity = copysignf(phi * config_.max_ang_velocity / M_PI, -sign_phi);
const float max_angle = config_.max_angle * M_PI / 180.0;
Expand Down Expand Up @@ -275,7 +274,7 @@ bool MeshController::initialize(const std::string& plugin_name,
map_ptr_ = mesh_map_ptr;
name_ = plugin_name;

angle_pub_ = node_->create_publisher<std_msgs::msg::Float32>("~/current_angle", rclcpp::QoS(1).transient_local());
angle_pub_ = node_->create_publisher<example_interfaces::msg::Float32>("~/current_angle", rclcpp::QoS(1).transient_local());

{ // cost max_lin_velocity
rcl_interfaces::msg::ParameterDescriptor descriptor;
Expand Down

0 comments on commit d634307

Please sign in to comment.