迷你无人车 Navigation 导航(3)

迷你无人车 Navigation 导航(3)

自己实现了对于迷你无人车关节的控制,由于原本的关节布置仅支持阿克曼转向,因此先进行阿克曼转向的控制

修改 URDF 文件

添加 transmission 标签,定义关节的驱动

<transmission name="right_rear_joint_trans"><type>transmission_interface/SimpleTransmission</type><joint name="right_rear_joint"><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface></joint><actuator name="right_rear_joint_motor"><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface><mechanicalReduction>1</mechanicalReduction></actuator></transmission>
<transmission name="front_steer_right_joint_trans"><type>transmission_interface/SimpleTransmission</type><joint name="front_steer_right_joint"><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface></joint><actuator name="front_steer_right_joint_motor"><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface><mechanicalReduction>1</mechanicalReduction></actuator>
</transmission>

注意位置控制关节中 limit 的设置,一开始均设置为 0,无法进行位置控制

<joint name="front_steer_right_joint" type="revolute"><origin rpy="0 0 0"  xyz="0.17 -0.21 0.102" /><parent link="base_link" /><child link="front_steer_right_link" /><axis xyz="0 0 1" />     <!-- charge steer direction default is 0 0 1--><limit lower="-0.69" upper="0.69" effort="2.0" velocity="1.0" /></joint>

配置 ros_control 插件

<gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><!-- <robotSimType>steer_bot_hardware_gazebo/SteerBotHardwareGazebo</robotSimType><legacyModeNS>false</legacyModeNS> --><robotNamespace>/steer_neor_mini</robotNamespace><robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType><legacyModeNS>true</legacyModeNS></plugin></gazebo>

注意命名空间的设置

配置 yaml 文件

在该文件中添加各关节控制器类型(速度控制/位置控制),以及控制器的 PID 系数

steer_neor_mini:joint_state_controller:type: joint_state_controller/JointStateControllerpublish_rate: 50# Velocity Controllers ----速度控制器---------------------left_rear_wheel_velocity_controller:type: effort_controllers/JointVelocityControllerjoint: left_rear_jointpid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}right_rear_wheel_velocity_controller:type: effort_controllers/JointVelocityControllerjoint: right_rear_jointpid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}left_front_wheel_velocity_controller:type: effort_controllers/JointVelocityControllerjoint: front_left_wheel_jointpid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}right_front_wheel_velocity_controller:type: effort_controllers/JointVelocityControllerjoint: front_right_wheel_jointpid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}# Position Controllers ---位置控制器-----------------------left_steering_hinge_position_controller:joint: front_steer_left_jointtype: effort_controllers/JointPositionControllerpid: {p: 0.5, i: 0.0, d: 0.0}right_steering_hinge_position_controller:joint: front_steer_right_jointtype: effort_controllers/JointPositionControllerpid: {p: 0.5, i: 0.0, d: 0.0}

配置 launch 文件

<?xml version="1.0"?>
<launch><arg name="x" default="0.0"/><arg name="y" default="0.0"/><arg name="z" default="0.0" /><arg name="roll" default="0.0"/><arg name="pitch" default="0.0"/><arg name="yaw" default="0.0"/><arg name="controllers" default="joint_state_controllerleft_rear_wheel_velocity_controller right_rear_wheel_velocity_controllerleft_front_wheel_velocity_controller right_front_wheel_velocity_controllerleft_steering_hinge_position_controller right_steering_hinge_position_controller"/><!-- Gazebo  --><!--Load the surrounding environment into Gazebo--><include file="$(find gazebo_ros)/launch/empty_world.launch" ><arg name="world_name" value="$(find neor_mini)/worlds/cooneo_office.world"/></include><!-- Load the robot description --><param name="robot_description" command="cat $(find neor_mini)/urdf/neor_mini_gazebo_sensors.urdf"/><!-- Load ros_controllers configuration parameters --><!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_ackermann_steering_controller.yaml" command="load"   /> --><!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_gains.yaml" command="load"   /> --><rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_joint_state_publisher.yaml" command="load"   /><!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_steer_bot_hardware_gazebo.yaml" command="load"   /> --><rosparam file="$(find steer_mini_gazebo)/mini_control/config/my_controller.yaml" command="load"/><!-- Spawn the controllers --><!-- <node pkg="controller_manager" type="spawner" name="controller_spawner"  args="joint_state_publisher ackermann_steering_controller" output="screen" respawn="false" /> --><node pkg="controller_manager" type="spawner" name="controller_spawner" output="screen" respawn="false" ns="/steer_neor_mini" args="$(arg controllers)"/><!-- Launch  the robot state publisher --><node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"><param name="publish_frequency" value="50.0"/><remap from="/joint_states" to="/steer_neor_mini/joint_states"/></node><!-- Launch a rqt steering GUI for publishing to /steer_bot/steer_drive_controller/cmd_vel --><!-- <node pkg="rqt_robot_steering" type="rqt_robot_steering" name="rqt_robot_steering" > --><!-- <param name="default_topic" value="ackermann_steering_controller/cmd_vel"/>                         default velocity control topic name --><!-- <param name="default_vx_max" value="1.0"/>                        linear velocity max value    m/s --><!-- <param name="default_vx_min" value="-1.0"/>                       linear velocity min value    m/s --><!-- <param name="default_vw_max" value="0.69"/>                    angular velocity max value  rad/s (adaptor for urdf joint limit) --><!-- <param name="default_vw_min" value="-0.69"/>                   angular velocity min value  rad/s (adaptor for urdf joint limit) --><!-- </node> --><!-- Start the Gazebo node and configure the location and posture of the accident when the model is loaded --><node name="spawn_vehicle" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model neor_mini -gazebo_namespace /gazebo -x $(arg x) -y $(arg y) -z $(arg z)-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"respawn="false" output="screen" /><!-- ******************************************************************************************************************************************* --><node name="laser_to_base_link" pkg="tf" type="static_transform_publisher" args="0.0 0.0 0.135 0 0 0 base_link laser_link 40 " /><node name="imu_to_base_link" pkg="tf" type="static_transform_publisher" args="-0.10 0.0 0.02 0 0 0 base_link imu_link 40 " /><node name="camera_to_base_link" pkg="tf" type="static_transform_publisher" args="0.12 0.0 0.12 0 0 0 base_link camera_link 40 " /></launch>

💡 注意各文件中命名空间的一致性

车轮速度解算

沿用四轮车的解算代码,更新车长、车宽以及车轮直径参数,目前只进行阿克曼转向的解算控制

#include <cmd_to_neor/wheelparams.h>
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float64.h>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <cmath>
#include <iostream>
#include <mutex>
#include "myTools.hpp"
using namespace std;
using namespace Eigen;ros::Publisher pub_vel_left_rear_wheel;
ros::Publisher pub_vel_right_rear_wheel;
ros::Publisher pub_vel_left_front_wheel;
ros::Publisher pub_vel_right_front_wheel;
ros::Publisher pub_pos_left_steering_hinge;
ros::Publisher pub_pos_right_steering_hinge;
cmd_to_neor::wheelparams w_params;
AidTool::Ptr aidtool;Matrix<double, 8, 3> coff_mat; // 机器人模型参数矩阵
Matrix<double, 3, 1> xyw;      // 机器人Vx, Vy, W向量
Matrix<double, 8, 1> p_xyw;// 机器人长的一半
const double half_len = 0.3492 / 2;
// 机器人宽的一半
const double half_wid = 0.36 / 2;
const double WHELL_DIA = 0.0625;
const double REDUCER_RATIO = 1.0;mutex mut;void computeWheelVel_pivotSteer();
void computeWheelVel_ackermannSteer(double linear_vel, double front, double rear);
double computeAckermannRatio(double vel);std_msgs::Float64 vel_left_rear_wheel;
std_msgs::Float64 vel_right_rear_wheel;
std_msgs::Float64 vel_left_front_wheel;
std_msgs::Float64 vel_right_front_wheel;
std_msgs::Float64 pos_left_steering_hinge;
std_msgs::Float64 pos_right_steering_hinge;double toRealVel(const double vel){return vel / (M_PI * WHELL_DIA) * REDUCER_RATIO;
}double toReaPos(const double pos){return pos * 180 / M_PI * REDUCER_RATIO;
}void robot_callback(const geometry_msgs::Twist::ConstPtr &msg)
{memset(&w_params, 0, sizeof(w_params));doublelinear_vel = msg->linear.x;double front_angle = msg->angular.z;computeWheelVel_ackermannSteer(linear_vel, front_angle, 0);vel_left_rear_wheel.data = toRealVel(w_params.lb_v);vel_right_rear_wheel.data = toRealVel(w_params.rb_v);vel_left_front_wheel.data = toRealVel(w_params.lf_v);vel_right_front_wheel.data = toRealVel(w_params.rf_v);pos_left_steering_hinge.data = w_params.lf_p;pos_right_steering_hinge.data = w_params.rf_p;cout << "lr_v:" << vel_left_rear_wheel.data << ";rr_v:" << vel_right_rear_wheel.data << \";lf_v:" << vel_left_front_wheel.data << ";rf_v:" << vel_right_front_wheel.data << endl;cout << "lf_p:" << pos_left_steering_hinge.data << ";rf_p:" << pos_right_steering_hinge.data << endl;cout << "--------------" << endl; lock_guard<mutex> lock(mut);pub_vel_left_rear_wheel.publish(vel_left_rear_wheel);pub_vel_right_rear_wheel.publish(vel_right_rear_wheel);pub_vel_left_front_wheel.publish(vel_left_front_wheel);pub_vel_right_front_wheel.publish(vel_right_front_wheel);pub_pos_left_steering_hinge.publish(pos_left_steering_hinge);pub_pos_right_steering_hinge.publish(pos_right_steering_hinge);mut.unlock();
}int main(int argc, char **argv)
{coff_mat << 1, 0, -half_wid,0, 1, half_len,1, 0, -half_wid,0, 1, -half_len,1, 0, half_wid,0, 1, -half_len,1, 0, half_wid,0, 1, half_len;const string vel_left_rear_wheel_topic = "/steer_neor_mini/left_rear_wheel_velocity_controller/command";const string vel_right_rear_wheel_topic = "/steer_neor_mini/right_rear_wheel_velocity_controller/command";const string vel_left_front_wheel_topic = "/steer_neor_mini/left_front_wheel_velocity_controller/command";const string vel_right_front_wheel_topic = "/steer_neor_mini/right_front_wheel_velocity_controller/command";const string pos_left_steering_hinge_topic = "/steer_neor_mini/left_steering_hinge_position_controller/command";const string pos_right_steering_hinge_topic = "/steer_neor_mini/right_steering_hinge_position_controller/command";aidtool = make_shared<AidTool>();ros::init(argc, argv, "cmd_to_neor");ros::NodeHandle nh;pub_vel_left_rear_wheel = nh.advertise<std_msgs::Float64>(vel_left_rear_wheel_topic, 1);pub_vel_right_rear_wheel = nh.advertise<std_msgs::Float64>(vel_right_rear_wheel_topic, 1);pub_vel_left_front_wheel = nh.advertise<std_msgs::Float64>(vel_left_front_wheel_topic, 1);pub_vel_right_front_wheel = nh.advertise<std_msgs::Float64>(vel_right_front_wheel_topic, 1);pub_pos_left_steering_hinge = nh.advertise<std_msgs::Float64>(pos_left_steering_hinge_topic, 1);pub_pos_right_steering_hinge = nh.advertise<std_msgs::Float64>(pos_right_steering_hinge_topic, 1);ros::Subscriber sub = nh.subscribe("/cmd_vel", 1, robot_callback);ros::spin();return 0;
}void computeWheelVel_pivotSteer()
{lock_guard<mutex> lock(mut);// 左前if (p_xyw(0, 0) == 0){if (p_xyw(1, 0) > 0){w_params.lf_p = M_PI_2;}else if (p_xyw(1, 0) < 0){w_params.lf_p = -M_PI_2;}else{w_params.lf_p = 0;}}else{w_params.lf_p = atan(p_xyw(1, 0) / p_xyw(0, 0));}if (p_xyw(0, 0) == 0.0 && p_xyw(1, 0) == 0.0){w_params.lf_v = 0.0;}else if (p_xyw(0, 0) == 0){w_params.lf_v = p_xyw(1, 0) / sin(w_params.lf_p);}else{w_params.lf_v = p_xyw(0, 0) / cos(w_params.lf_p);}// 左后if (p_xyw(2, 0) == 0){if (p_xyw(3, 0) > 0){w_params.lb_p = M_PI_2;}else if (p_xyw(3, 0) < 0){w_params.lb_p = -M_PI_2;}else{w_params.lb_p = 0;}}else{w_params.lb_p = atan(p_xyw(3, 0) / p_xyw(2, 0));}if (p_xyw(2, 0) == 0.0 && p_xyw(3, 0) == 0.0){w_params.lb_v = 0.0;}else if (p_xyw(2, 0) == 0){w_params.lb_v = p_xyw(3, 0) / sin(w_params.lb_p);}else{w_params.lb_v = p_xyw(2, 0) / cos(w_params.lb_p);}// 右后if (p_xyw(4, 0) == 0){if (p_xyw(5, 0) > 0){w_params.rb_p = M_PI_2;}else if (p_xyw(5, 0) < 0){w_params.rb_p = -M_PI_2;}else{w_params.rb_p = 0;}}else{w_params.rb_p = atan(p_xyw(5, 0) / p_xyw(4, 0));}if (p_xyw(4, 0) == 0.0 && p_xyw(5, 0) == 0.0){w_params.rb_v = 0.0;}else if (p_xyw(4, 0) == 0){w_params.rb_v = p_xyw(5, 0) / sin(w_params.rb_p);}else{w_params.rb_v = p_xyw(4, 0) / cos(w_params.rb_p);}// 右前if (p_xyw(6, 0) == 0){if (p_xyw(7, 0) > 0){w_params.rf_p = M_PI_2;}else if (p_xyw(7, 0) < 0){w_params.rf_p = -M_PI_2;}else{w_params.rf_p = 0;}}else{w_params.rf_p = atan(p_xyw(7, 0) / p_xyw(6, 0));}if (p_xyw(6, 0) == 0.0 && p_xyw(7, 0) == 0.0){w_params.rf_v = 0.0;}else if (p_xyw(6, 0) == 0){w_params.rf_v = p_xyw(7, 0) / sin(w_params.rf_p);}else{w_params.rf_v = p_xyw(6, 0) / cos(w_params.rf_p);}mut.unlock();
}void computeWheelVel_ackermannSteer(double linear_vel, double front, double rear)
{lock_guard<mutex> lock(mut);// cout << "front_angle: " << aidtool->rad2deg(front) << "\t rear_angle: " << aidtool->rad2deg(rear) << endl;double d_vertical = 0.0, l_up = half_len;if (front != 0){d_vertical = 2 * half_len * cos(front) * cos(rear) / sin(front - rear);l_up = 2 * half_len * sin(front) * cos(rear) / sin(front - rear);// cout << "d_vertical: " << d_vertical << "\tl_up: " << l_up << endl;w_params.lf_p = atan(2 * half_len * sin(front) * cos(rear) / (2 * half_len * cos(front) * cos(rear) - half_wid * sin(front - rear)));w_params.rf_p = atan(2 * half_len * sin(front) * cos(rear) / (2 * half_len * cos(front) * cos(rear) + half_wid * sin(front - rear)));w_params.lb_p = atan(2 * half_len * cos(front) * sin(rear) / (2 * half_len * cos(front) * cos(rear) - half_wid * sin(front - rear)));w_params.rb_p = atan(2 * half_len * cos(front) * sin(rear) / (2 * half_len * cos(front) * cos(rear) + half_wid * sin(front - rear)));}double Rc = sqrt(pow(half_len - l_up, 2) + pow(d_vertical, 2));if (Rc == 0){w_params.lf_v = linear_vel;w_params.rf_v = linear_vel;w_params.lb_v = linear_vel;w_params.rb_v = linear_vel;}else{double Rlf = sqrt(pow(l_up, 2) + pow(d_vertical - half_wid, 2));double Rrf = sqrt(pow(l_up, 2) + pow(d_vertical + half_wid, 2));double Rlr = sqrt(pow(2 * half_len - l_up, 2) + pow(d_vertical - half_wid, 2));double Rrr = sqrt(pow(2 * half_len - l_up, 2) + pow(d_vertical + half_wid, 2));double angular_vel = linear_vel / Rc;w_params.lf_v = angular_vel * Rlf;w_params.rf_v = angular_vel * Rrf;w_params.lb_v = angular_vel * Rlr;w_params.rb_v = angular_vel * Rrr;}mut.unlock();
}double computeAckermannRatio(double vel)
{double corner_stiffness = -100000.0;double mass = 250;lock_guard<mutex> lock(mut);double ratio = 1 - 4 * half_len * corner_stiffness / (2 * half_len * corner_stiffness - mass * pow(vel, 2));mut.unlock();return ratio;
}

话题组织

完整的话题组织如下,可以通过 Logitech 手柄控制 Gazebo 中的迷你无人车以阿克曼转向方式运动

在这里插入图片描述

实际效果如下

在这里插入图片描述

下一步计划修改 URDF 模型进行四轮转向和原地转向控制

参考

阿克曼结构移动机器人的gazebo仿真(五)

阿克曼结构移动机器人的gazebo仿真(六)

https://wiki.ros.org/urdf/XML/Transmission

https://wiki.ros.org/urdf/XML/joint

探究–gazebo里 关节是如何动起来的____实现默认插件joint控制

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.hqwc.cn/news/105973.html

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

Java“牵手”ebay商品详情数据,ebay商品详情API接口,ebayAPI接口申请指南

天猫平台商品详情接口是开放平台提供的一种API接口&#xff0c;通过调用API接口&#xff0c;开发者可以获取天猫商品的标题、价格、库存、月销量、总销量、库存、详情描述、图片等详细信息 。 获取商品详情接口API是一种用于获取电商平台上商品详情数据的接口&#xff0c;通过…

python关闭指定进程以excel为例

先说下环境&#xff1a; Excel版本&#xff1a; Python2.7.13和Python3.10.4并存。 2、打开两个excel工作簿 看进程是这样的&#xff1a; 3、用python编程kill进程 # -*- coding: utf-8 -*- import os proc_nameEXCEL.EXE if __name__ __main__:os.system(taskkill /im {} /…

SSM - Springboot - MyBatis-Plus 全栈体系(六)

第二章 SpringFramework 四、SpringIoC 实践和应用 3. 基于 注解 方式管理 Bean 3.1 实验一&#xff1a;Bean 注解标记和扫描 (IoC) 3.1.1 注解理解 和 XML 配置文件一样&#xff0c;注解本身并不能执行&#xff0c;注解本身仅仅只是做一个标记&#xff0c;具体的功能是框…

Kafka3.0.0版本——消费者(消费者组初始化流程图解)

一、消费者组初始化流程图解 每个consumer都发送JoinGroup请求&#xff0c;如下图所示&#xff1a; 选出一个consumer作为leader&#xff0c;如下图所示&#xff1a; 把要消费的topic情况发送给leader 消费者&#xff0c;如下图所示&#xff1a; leader会负责制定消费方案…

jupyter 格式化与快捷键

1、标题&#xff1a; # 一级标题 ## 二级标题 ### 三级标题 2、 加粗文本&#xff1a; **加粗文本** 3、斜体文本&#xff1a; _斜体_ 4、删除线 ~删除线~ 5、高亮文本 高亮文本 6、区块引用 > 我是引用文字 >> 我是第二层 >&g…

自然语言处理-词向量模型-Word2Vec

通常数据的维度越高&#xff0c;能提供的信息也就越多&#xff0c;从而计算结果的可靠性就更值得信赖 如何来描述语言的特征呢&#xff0c;通常都在词的层面上构建特征&#xff0c;Word2Vec就是要把词转换成向量 假设现在已经拿到一份训练好的词向量&#xff0c;其中每一个词都…

cmake构建和编译

什么是CMake&#xff1f; CMake本身是一个工具集&#xff0c;由五个可执行的程序组成&#xff1a;cmake、ctest、cpack、cmake-gui和ccmake&#xff0c;其中cmake可以说是出镜率最高的明星级别程序了&#xff0c;它用于在构建项目的第一步&#xff0c;进行项目的配置、生成和构…

NLP(1)--NLP基础与自注意力机制

目录 一、词向量 1、概述 2、向量表示 二、词向量离散表示 1、one-hot 2、Bag of words 3、TF-IDF表示 4、Bi-gram和N-gram 三、词向量分布式表示 1、Skip-Gram表示 2、CBOW表示 四、RNN 五、Seq2Seq 六、自注意力机制 1、注意力机制和自注意力机制 2、单个输出…

Voxel R-CNN:基于体素的高性能 3D 目标检测

论文地址&#xff1a;https://arxiv.org/abs/2012.15712 论文代码&#xff1a;https://github.com/djiajunustc/Voxel-R-CNN 论文背景 基于点的方法具有较高的检测精度&#xff0c;但基于点的方法通常效率较低&#xff0c;因为对于点集抽象来说&#xff0c;使用点表示来搜索最…

react中使用Modal.confirm数据不更新的问题解决

在使用Modal.confirm的时候今天发现了个疑惑的问题&#xff0c;为什么我明明从新set了数据而页面视图没有变化&#xff0c;查了一下官方文档找到了答案&#xff0c;解决了这个问题&#xff0c;特意在这里留下痕迹。 import { Button, Col, Form, Input, Modal, Radio, Row, Se…

开赛啦!第六届“中国法研杯”司法人工智能挑战赛精彩启幕

9月9日&#xff0c;第六届“中国法研杯”司法人工智能挑战赛&#xff08;简写为“LAIC2023”&#xff09;在福建厦门正式拉开帷幕&#xff0c;主办方中国司法大数据研究院&#xff08;以下简称“中国法研”&#xff09;以及厦门市思明区政府、厦门海丝办有关领导共同参加了启动…

Linux文件属性操作函数

access函数 chmod函数 chown函数 修改文件的所在组或者所有者 truncate函数