This commit is contained in:
Baptiste LEROY 2025-11-18 15:08:21 +01:00
parent 411ebd5994
commit 4d76991835
4 changed files with 138 additions and 0 deletions

44
CMakeLists.txt Normal file
View File

@ -0,0 +1,44 @@
cmake_minimum_required(VERSION 3.8)
project(ros_midterm)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
add_executable(imu_sub src/imu_sub.cpp)
ament_target_dependencies(imu_sub rclcpp sensor_msgs)
add_executable(cmd_pub src/cmd_pub.cpp)
ament_target_dependencies(cmd_pub rclcpp geometry_msgs)
install(TARGETS
imu_sub
cmd_pub
DESTINATION lib/${PROJECT_NAME}
)
ament_package()

39
cmd_pub.cpp Normal file
View File

@ -0,0 +1,39 @@
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include <cstdlib>
#include <ctime>
class CmdPublisher : public rclcpp::Node
{
public:
CmdPublisher() : Node("cmd_pub")
{
publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
timer_ = this->create_wall_timer(
std::chrono::seconds(1),
std::bind(&CmdPublisher::timer_callback, this)
);
std::srand(std::time(nullptr)); // initialisation du générateur aléatoire
}
private:
void timer_callback()
{
geometry_msgs::msg::Twist msg;
msg.angular.z = ((double)std::rand() / RAND_MAX) * 2.0 - 1.0; // entre -1 et 1
publisher_->publish(msg);
RCLCPP_INFO(this->get_logger(), "Published angular velocity around z: %.3f rad/s", msg.angular.z);
}
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<CmdPublisher>());
rclcpp::shutdown();
return 0;
}

32
imu_sub.cpp Normal file
View File

@ -0,0 +1,32 @@
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/imu.hpp"
class IMUSubscriber : public rclcpp::Node
{
public:
IMUSubscriber() : Node("imu_sub")
{
subscription_ = this->create_subscription<sensor_msgs::msg::Imu>(
"/imu",
10,
std::bind(&IMUSubscriber::imu_callback, this, std::placeholders::_1)
);
}
private:
void imu_callback(const sensor_msgs::msg::Imu::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "Angular velocity around z: %.3f rad/s", msg->angular_velocity.z);
}
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr subscription_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<IMUSubscriber>());
rclcpp::shutdown();
return 0;
}

23
package.xml Normal file
View File

@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros_midterm</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="baptiste.leroy@ecam.fr">ros</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>