商丘做网站的公司有哪些,wordpress支持响应式吗,百度怎么优化网站关键词,wordpress建立网站实例前段时间写了文章#xff0c;通过修改sdf、urdf模型的方法#xff0c;在Gazebo中添加悬浮模型方法 / Gazebo中模型如何不因重力下落#xff1a;在Gazebo中添加悬浮模型方法 / Gazebo中模型如何不因重力下落#xff1a;修改sdf、urdf模型_sagima_sdu的博客-CSDN博客
今天讲…前段时间写了文章通过修改sdf、urdf模型的方法在Gazebo中添加悬浮模型方法 / Gazebo中模型如何不因重力下落在Gazebo中添加悬浮模型方法 / Gazebo中模型如何不因重力下落修改sdf、urdf模型_sagima_sdu的博客-CSDN博客
今天讲一下如何通过键盘来控制其移动监听键盘输入并根据按键调整模型的位置然后通过调用set_model_state函数来更新模型在Gazebo中的状态
程序举例
首先我们先通过一个程序实现在指定的空间坐标生成一个指定的模型
注意如果要使用的话需要修改程序中指定的模型名称和模型的路径
# -*- coding: utf-8 -*-
#!/usr/bin/env python
Authorsagima使用Gazebo仿真环境中生成一个名为aruco_cubo_hover的模型
python model.py
程序运行在Python2.7环境下。
import os
import rospy
from gazebo_msgs.msg import ModelState
from gazebo_msgs.srv import DeleteModel, SpawnModel
from std_msgs.msg import Header
from geometry_msgs.msg import Pose, Point# 初始化ROS节点
rospy.init_node(spawn_aruco_cubo_hover, anonymousTrue)# 定义生成模型的函数
def spawn_aruco_cubo_hover():model_name aruco_cubo_hovermodel_path /home/sjh/project/Tiago_ws/src/pal_gazebo_worlds/models/aruco_cube_hover/aruco_cube_hover.sdf# 在这里修改目标位置initial_pose Pose(positionPoint(x0.8, y0, z1))# 从文件加载模型with open(model_path, r) as f:model_xml f.read()# 调用Gazebo的SpawnModel服务spawn_model rospy.ServiceProxy(/gazebo/spawn_sdf_model, SpawnModel)resp_sdf spawn_model(model_name, model_xml, , initial_pose, world)if resp_sdf.success:rospy.loginfo(模型 {} 生成成功。.format(model_name))else:rospy.logerr(模型 {} 生成失败。.format(model_name))# 调用生成模型的函数
if __name__ __main__:try:spawn_aruco_cubo_hover()except rospy.ROSInterruptException:pass上面的程序没有问题的话就可以为其加入通过键盘控制的功能了
# -*- coding: utf-8 -*-
#!/usr/bin/env python
Authorsagima使用Gazebo仿真环境中生成一个名为aruco_cubo_hover的模型并通过键盘控制模型运动
python model_with_keyboard_control.py
程序运行在Python2.7环境下。
import os
import rospy
from gazebo_msgs.msg import ModelState
from gazebo_msgs.srv import SetModelState, GetModelState
from std_msgs.msg import Header
from geometry_msgs.msg import Pose, Point
import sys
import select
import tty
import termios# 初始化ROS节点
rospy.init_node(spawn_aruco_cubo_hover, anonymousTrue)# 保存终端设置
old_settings termios.tcgetattr(sys.stdin)
tty.setcbreak(sys.stdin.fileno())# 定义运动速度
move_speed 0.1# 定义生成模型的函数
def spawn_aruco_cubo_hover(initial_pose):model_name aruco_cubo_hovermodel_path /home/sjh/project/Tiago_ws/src/pal_gazebo_worlds/models/aruco_cube_hover/aruco_cube_hover.sdf# 从文件加载模型with open(model_path, r) as f:model_xml f.read()# 调用Gazebo的SpawnModel服务spawn_model rospy.ServiceProxy(/gazebo/spawn_sdf_model, SpawnModel)resp_sdf spawn_model(model_name, model_xml, , initial_pose, world)if resp_sdf.success:rospy.loginfo(模型 {} 生成成功。.format(model_name))else:rospy.logerr(模型 {} 生成失败。.format(model_name))# 定义设置模型状态的函数
def set_model_state(model_name, pose):model_state ModelState()model_state.model_name model_namemodel_state.pose poseset_model_state rospy.ServiceProxy(/gazebo/set_model_state, SetModelState)set_model_state(model_state)# 中文提示
print(按下以下键盘按键来控制模型运动)
print(W: 向前移动)
print(S: 向后移动)
print(A: 向左移动)
print(D: 向右移动)
print(Q: 上升)
print(E: 下降)
print(CtrlC: 退出程序)try:# 定义初始位置initial_pose Pose(positionPoint(x0.8, y0, z1))# 主循环持续监听键盘输入并控制模型运动while True:if select.select([sys.stdin], [], [], 0)[0] [sys.stdin]:key sys.stdin.read(1)if key w:initial_pose.position.x move_speedelif key s:initial_pose.position.x - move_speedelif key a:initial_pose.position.y move_speedelif key d:initial_pose.position.y - move_speedelif key q:initial_pose.position.z move_speedelif key e:initial_pose.position.z - move_speedelif key \x03: # CtrlCbreak# 调用设置模型状态的函数set_model_state(aruco_cubo_hover, initial_pose)
except rospy.ROSInterruptException:pass
finally:# 恢复终端设置termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)注意如果要使用的话需要修改程序中指定的模型名称和模型的路径同时如果需要修改按键记得在中文提示中一并修改