[vlog]Autoware Carla G29 自动驾驶仿真_哔哩哔哩_bilibili
话接上文,在我之前一篇博客中已经讲解了如何给罗技29方向盘装上力反馈,也就是在拨动方向盘的时候感觉有一个力组织你过度的拨动方向盘,其实它真正的用处是用于实现对方向盘发送控制指令,这不就是所谓的自动驾驶嘛!!!!(2条消息) logitech G29 Carla_”悟道“的博客-CSDN博客
最上面B站上有一个视频,展示的是Autoware发送rviz中虚拟方向盘的控制指令,Up写了一个转发的ros节点,将控制指令给转发出来,通过对罗技29的力反馈句柄上发送控制指令,实现了如此酷炫的效果,我也尝试自己写出一个转发节点,今天开源给大家,供大家参考;
#include <iostream> //文件流头文件
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/joy.hpp"
#include "ros_g29_force_feedback/msg/force_feedback.hpp" //之前博客中的力反馈头文件
class Voyager : public rclcpp::Node
{
public:
Voyager() : Node("voyager") //转发节点的名字叫voyager
{
subscription_=this->create_subscription<sensor_msgs::msg::Joy>(
"/joy", 10, std::bind(&Voyager::callback, this, std::placeholders::_1)); //订阅者
publisher_ = this->create_publisher<ros_g29_force_feedback::msg::ForceFeedback>(
"/ff_target", 10); //发布者
}
private:
void callback(const sensor_msgs::msg::Joy::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "Steering tire angle: %f", msg->axes[0]);
auto ff_msg = ros_g29_force_feedback::msg::ForceFeedback();
// ff_msg.header.stamp = msg->header.stamp;
ff_msg.header.stamp = msg->header.stamp;
ff_msg.header.frame_id=" ";
// ff_msg.position = msg->axes[0];
if(msg->axes[0] > 0){
ff_msg.position = -1 * (msg->axes[0]+0.09);
}
else if (msg->axes[0] < 0){
ff_msg.position = -1 * msg->axes[0] + 0.09;
}
else {
ff_msg.position = 0;
}
// ff_msg.position = -1 * (msg->axes[0]+0.09);
ff_msg.torque = 0.5;
// RCLCPP_INFO(this->get_logger());
publisher_->publish(ff_msg);
}
rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr subscription_;
rclcpp::Publisher<ros_g29_force_feedback::msg::ForceFeedback>::SharedPtr publisher_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<Voyager>());
rclcpp::shutdown();
return 0;
}
这里面有一个Ubuntu的包叫joy,一般用于各鼠标键盘按压数据的接收的,我们这里可以用他来记录罗技29的转动角度(通过录rosbag的方式),到时候只需要播放bag包,罗技29方向盘就可以自己转动了;如果你想直接从autoware中获取方向盘的转动角度,也是可以的,需要修改一个subscribe(订阅者)的msg,然后根据发送过来的消息,将其中重要的数据,方向盘的转动角度,进行转发,转发给罗技方向盘就可以;
package.xml
<?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>voyager_pub_sub</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="m0_48707860@example.com">voyager</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<depend>std_msgs</depend>
<depend>rclcpp</depend>
<depend>ros_g29_force_feedback</depend>
<depend>sensor_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>
CMakeLists.txt怎么写呢?
cmake_minimum_required(VERSION 3.8)
project(voyager_pub_sub)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# 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(rosidl_default_generators REQUIRED)
find_package(ros_g29_force_feedback REQUIRED)
find_package(sensor_msgs REQUIRED)
# find_package(joy REQUIRED)
set(dependencies
rclcpp
std_msgs
ros_g29_force_feedback
sensor_msgs
)
# Generate project targer with msg
# rosidl_generate_interfaces(${PROJECT_NAME}
# "msg/ForceFeedback.msg"
# DEPENDENCIES rosidl_default_generators std_msgs)
# Add executable
add_executable(voyager_node src/voyager.cpp)
ament_target_dependencies(voyager_node ${dependencies})
install(TARGETS voyager_node
DESTINATION lib/${PROJECT_NAME})
ament_export_dependencies(rosidl_default_runtime)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
其中msg文件下存放的是,之前博客中罗技29的消息体;
include中没有东西;
然后C++代码写完,剩下的就是编译了,把这个节点编译出来
source /autoware/install/setup.bash
colcon build --allow-overriding autoware_auto_vehicle_msg
1.脚本1:用于更新代码中罗技29的event口
由于每次罗技29插在电脑上,开机重启的时候这个event可能会改变,所以我用shell脚本,写了一个找到罗技29的event,并修改代码;
#!/bin/bash
event=$(cat /proc/bus/input/devices | grep "Logitech G29 Driving Force Racing Wheel" -A 5 | grep "Handlers" | grep -o "event[0-9]*")
echo "Event number: $event"
sed -i "s|/dev/input/event[0-9]*|/dev/input/$event|" Lg29/ros2_ws/src/ros-g29-force-feedback/config/g29.yaml
echo "Event changed"
2.脚本2:用于启动罗技29的节点
#!/bin/bash
gnome-terminal -e 'ls -l'
source /opt/ros/galactic/setup.bash
cd Lg29/ros2_ws/
source install/setup.bash
ros2 run ros_g29_force_feedback g29_force_feedback --ros-args --params-file src/ros-g29-force-feedback/config/g29.yaml
3.脚本3:启动转发节点
#!/bin/bash
gnome-terminal -e 'ls -l'
cd record_g29/
source install/setup.bash
ros2 run voyager_pub_sub voyager_node
4.脚本4:如果是自己通过罗技29录制的rosbag,可以选择播放rosbag,也可以选择从autoware中把节点转发出来,然后启动autoware的节点:
今日思考:其实可以对方向盘的转动做出平滑,这样方向盘的转动会更舒缓;期待大家的改进!!!