一、首先在ROS环境中对G29 的数据进行解析并发布。
使用ROS自带的Joy包就可以启动G29摇杆
1.首先安装两个ROS 依赖包
#注意自己对应的ros版本
sudo apt-get install ros-melodic-pacmod*
sudo apt-get install ros-melodic-joy*
2.创建一个launch文件,命名为g29.launch,写入以下内容
<?xml version="1.0"?>
<launch>
<group ns="G29">
<node pkg="joy" type="joy_node" name="joy">
<param name="coalesce_interval" type="double" value="0.02"/>
<param name="default_trig_val" value="true"/>
<!-- param name="deadzone" value="0.0"/ -->
<param name="dev" value="/dev/input/js0" type="string "/>
<param name="deadzone" value="0.05" type="double"/>
<!-- aram name="autorepeat_rate" value="10" type="double"/-->
</node>
</group>
</launch>
这里把命名空间改为G29,这是由于我们还需要使用手柄式的遥控器(也是用的Joy包),这里主要是为了避免冲突。
参考链接: ROS中使用罗技G29遥控器
3.这时候将G29插入电脑USB接口,方向盘会进行自检,分别旋转到逆时针和顺时针的最大值。
二、在自己的工作空间下,写一个消息类型转换的代码,订阅罗技自身的数据并将其转换为carla的消息类型。
代码如下(C++):
#include <iostream>
#include <ros/ros.h>
#include <joint_control/CarlaEgoVehicleControl.h>
#include <sensor_msgs/Joy.h>
#include <cmath>
class joy_to_carla
{
public:
ros::NodeHandle nh;
ros::Publisher pub;
ros::Subscriber sub;
// 车长/m
float car_length;
// 车的最大转向角度,单位角度
float max_turn_angular;
// 车的最大速度,单位m/s
float max_velocity;
// 订阅的回调函数
joy_to_carla()
{
nh.param<float>("Carla/car_length", car_length, 1.0);
nh.param<float>("Carla/max_turn_angular", max_turn_angular, 30.0);
nh.param<float>("Carla/max_velocity", max_velocity, 10.0);
// 订阅罗技的joy消息
sub = nh.subscribe<sensor_msgs::Joy>("/G29/joy", 100, &joy_to_carla::cb_joy_to_carla, this);
// 发布转化的carla消息
pub = nh.advertise<joint_control::CarlaEgoVehicleControl>("/carla/ego_vehicle/vehicle_control_cmd", 100);
};
void cb_joy_to_carla(const sensor_msgs::Joy::ConstPtr &msg)
{
// 要发布给carla的消息
joint_control::CarlaEgoVehicleControl VehicleControl;
// 1.0 计算线速度
// 由于axes[2]前进油门和axes[3]倒车油门范围均为-1~1,因此根据是否为未踩判断用哪个
if (msg->axes[2] != -1.0)
{
// 加上1后范围在0~2,因此除2
VehicleControl.throttle = (msg->axes[2] + 1) * max_velocity / 2;
// 前进档位
VehicleControl.gear = 1;
// 无法倒车
VehicleControl.reverse = false;
}
else if (msg->axes[3] != -1)
{
VehicleControl.throttle = -(msg->axes[3] + 1) * max_velocity / 2;
// 倒退档位
VehicleControl.gear = -1;
// 允许倒车
VehicleControl.reverse = true;
}
else
// 为0的时候说明两者都为0或者都不为0,此时速度应该为0
VehicleControl.throttle = 0.0;
// 2.0 计算角速度
// 运动学公式: 转弯角度 = arctan(车长*角速度/线速度) 的逆运算
if (VehicleControl.throttle == 0.0)
// 速度为0的时候的角速度(默认速度为1),取负号是因为方向盘方向反了
VehicleControl.steer = tan(-msg->axes[0] * max_turn_angular * M_PI / 180) / car_length;
else
VehicleControl.steer = tan(-msg->axes[0] * max_turn_angular * M_PI / 180) * VehicleControl.throttle / car_length;
// 3.0 发布VehicleControl
pub.publish(VehicleControl);
int main(int argc, char *argv[])
{
// 初始化节点
ros::init(argc, argv, "g29_joy_control_carla");
joy_to_carla J;
ros::spin();
return 0;
}
在CMakeLists文件中加入以下内容:
cmake_minimum_required(VERSION 3.0.2)
project(joint_control)
find_package(catkin REQUIRED COMPONENTS
message_generation
roscpp
rospy
std_msgs
sensor_msgs
)
add_message_files(
DIRECTORY msg
FILES
CarlaEgoVehicleControl.msg
)
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)
catkin_package(
CATKIN_DEPENDS message_runtime roscpp rospy std_msgs sensor_msgs
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(g29_joy_control_carla src/g29_joy_control_carla.cpp)
add_dependencies(g29_joy_control_carla ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(g29_joy_control_carla ${catkin_LIBRARIES})
在消息类型的文件夹中拷入carla_ros_bridge中的carla_msgs中的CarlaEgoVehicleControl.msg文件
相信有安装好carla 的朋友都安装了carla_ros_bridge,如果没有下载功能包,可以看我前面的博客: carla-ros-bridge下载与安装
再写一个config文件,这里命名为config.yaml:
Carla:
car_length: 1.2 # 车长,单位m
max_turn_angular: 27.5 # 车的最大转向角度,单位角度
max_velocity: 1 # 车的最大速度,单位m/s
再编写一个launch文件:
<launch>
<rosparam file="$(find joint_control)/config/config.yaml" command="load" />
<node pkg="joint_control" type="g29_joy_control_carla" name="g29_joy_control_carla" output="screen" respawn="true" />
<include file="$(find joint_control)/launch/g29.launch"/>
</launch>
将此launch文件和g29.launch文件放在一起
至此,功能包已经写好,可以开始编译啦
编译通过后,启动launch文件
然后启动carla二进制以及carla_ros_bridge_with_example_ego_vehicle.launch文件
此时即可通过罗技G29控制carla
可以通过rostopic echo打印查看罗技方向盘的信息和carla的信息
#打印罗技信息
rostopic echo /G29/joy
#打印carla信息
rostopic echo /carla/ego_vehicle/vehicle_control_cmd