Failed to compile node with custom msg created in same package
This question is very similar to: https://answers.ros.org/question/3065... but it dosen't solve my problem. The error that I get is that the custom message library #include "optimus_rover/msg/wheel_angles.hpp"
is not found. I've checked that the library .hpp and .h is generated fine under
/home/$USER/dev_ws/install/optimus_rover/include/optimus_rover/msg
To explain I have 1 package called optimus_rover with the following layout:
/optimus_rover
CMakeLists.txt
/include
/optimus_rover
/msg
WheelAngles.msg
package.xml
/src
main.cpp
My CMakeLists.txt file looks like this:
cmake_minimum_required(VERSION 3.5)
project(optimus_rover)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
# find_package(builtin_interfaces REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/WheelAngles.msg"
# DEPENDENCIES builtin_interfaces
)
add_executable(${PROJECT_NAME}_node src/main.cpp)
ament_target_dependencies(${PROJECT_NAME}_node rclcpp std_msgs geometry_msgs sensor_msgs)
install(TARGETS
${PROJECT_NAME}_node
DESTINATION lib/${PROJECT_NAME})
ament_package()
My main.cpp node looks like this:
// Include important C++ header files that provide class
// templates for useful operations.
#include <functional> // Arithmetic, comparisons, and logical operations
#include <memory> // Dynamic memory management
#include <string> // String functions
// ROS Client Library for C++
// Allows use of the most common elements of ROS 2
#include "rclcpp/rclcpp.hpp"
// Built-in message type that will be used to publish data
#include "std_msgs/msg/string.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "std_msgs/msg/float32_multi_array.hpp"
#include "optimus_rover/msg/wheel_angles.hpp"
using std::placeholders::_1;
// Create the node class named PublishingSubscriber which inherits the attributes
// and methods of the rclcpp::Node class.
class PublishingSubscriber : public rclcpp::Node
{
public:
// Constructor creates a node named publishing_subscriber.
// The published message count is initialized to 0.
PublishingSubscriber()
: Node("publishing_subscriber")
{
// Create the subscription.
// The topic_callback function executes whenever data is published
// to the 'addison' topic.
subscription_ = this->create_subscription<geometry_msgs::msg::Twist>(
"cmd_vel", 10, std::bind(&PublishingSubscriber::topic_callback, this, _1));
// Publisher publishes String messages to a topic named "addison2".
// The size of the queue is 10 messages.
pose_publisher_ = this->create_publisher<std_msgs::msg::Float32MultiArray>("wheel_pose_setpoints",10);
vel_publisher_ = this->create_publisher<std_msgs::msg::Float32MultiArray>("wheel_vel_setpoints",10);
}
private:
// Receives the String message that is published over the topic
void topic_callback(const geometry_msgs::msg::Twist::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "LinSpeed: '%f', AngSpeed: '%f'",
msg->linear.x,
msg->angular.z
);
// Create a new message of type String
auto pose_msg = std_msgs::msg::Float32MultiArray();
auto vel_msg = std_msgs::msg::Float32MultiArray();
// // Publish the message to the topic
// pose_publisher_->publish(pose_msg);
// vel_publisher_->publish(vel_msg);
RCLCPP_INFO(this->get_logger(), "End callback");
}
// Declare the subscription attribute
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_;
// Declaration of the publisher_ attribute
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr vel_publisher_;
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr pose_publisher_;
};
// Node execution starts here
int main(int argc, char * argv[])
{
// Initialize ROS 2
rclcpp::init(argc, argv);
// Start processing data from the node as well as the callbacks
rclcpp::spin(std::make_shared<PublishingSubscriber>());
// Shutdown the node when finished
rclcpp::shutdown();
return 0;
}
My package.xml looks like this:
<?xml version="1.0"?>
<?xml-model ...