使用键盘控制Franka机械臂运动

功能说明

使用键盘按键,可以控制franka机械臂7个关节角,已在真机上验证。

代码

主要使用的是官方包内的 franka_example_controllers

1、修改 include下的 joint_position_example_controller.h, 改为如下:

// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
//  技术交流/服务 v: L2622452304
#pragma once#include <array>
#include <string>
#include <vector>#include <controller_interface/multi_interface_controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/robot_hw.h>
#include <ros/node_handle.h>
#include <ros/time.h>
#include <ros/ros.h>
#include <std_msgs/Float32MultiArray.h>namespace franka_example_controllers {class JointPositionExampleController : public controller_interface::MultiInterfaceController<hardware_interface::PositionJointInterface> {public:ros::NodeHandle n;bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;void joint_command_callback(const std_msgs::Float32MultiArray &msg);void starting(const ros::Time&) override;void update(const ros::Time&, const ros::Duration& period) override;std::array<float, 7> joints_position_change = {0.0,0.0,0.0,0.0,0.0,0.0,0.0};private:hardware_interface::PositionJointInterface* position_joint_interface_;std::vector<hardware_interface::JointHandle> position_joint_handles_;ros::Duration elapsed_time_;std::array<double, 7> initial_pose_{};};}  // namespace franka_example_controllers

2、修改 src下的 joint_position_example_controller.cpp, 改为如下:

// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include <franka_example_controllers/joint_position_example_controller.h>#include <cmath>#include <controller_interface/controller_base.h>
#include <hardware_interface/hardware_interface.h>
#include <hardware_interface/joint_command_interface.h>
#include <pluginlib/class_list_macros.h>
// #include <ros/ros.h>namespace franka_example_controllers {bool JointPositionExampleController::init(hardware_interface::RobotHW* robot_hardware,ros::NodeHandle& node_handle) {n = node_handle;position_joint_interface_ = robot_hardware->get<hardware_interface::PositionJointInterface>();if (position_joint_interface_ == nullptr) {ROS_ERROR("JointPositionExampleController: Error getting position joint interface from hardware!");return false;}std::vector<std::string> joint_names;if (!node_handle.getParam("joint_names", joint_names)) {ROS_ERROR("JointPositionExampleController: Could not parse joint names");}if (joint_names.size() != 7) {ROS_ERROR_STREAM("JointPositionExampleController: Wrong number of joint names, got "<< joint_names.size() << " instead of 7 names!");return false;}position_joint_handles_.resize(7);for (size_t i = 0; i < 7; ++i) {try {position_joint_handles_[i] = position_joint_interface_->getHandle(joint_names[i]);} catch (const hardware_interface::HardwareInterfaceException& e) {ROS_ERROR_STREAM("JointPositionExampleController: Exception getting joint handles: " << e.what());return false;}}std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};for (size_t i = 0; i < q_start.size(); i++) {if (std::abs(position_joint_handles_[i].getPosition() - q_start[i]) > 0.1) {ROS_ERROR_STREAM("JointPositionExampleController: Robot is not in the expected starting position for ""running this example. Run `roslaunch franka_example_controllers move_to_start.launch ""robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first.");return false;}}return true;
}void JointPositionExampleController::joint_command_callback(const std_msgs::Float32MultiArray &msg){for (size_t i = 0; i < 7; ++i) {joints_position_change[i] = msg.data[0];}
}void JointPositionExampleController::starting(const ros::Time& /* time */) {// for (size_t i = 0; i < 7; ++i) {//   initial_pose_[i] = position_joint_handles_[i].getPosition();// }// elapsed_time_ = ros::Duration(0.0);// ros::init("keyboard_subscriber");ros::Subscriber joint_sub = n.subscribe("/keyboard", 1, &JointPositionExampleController::joint_command_callback,this);ros::spin();
}void JointPositionExampleController::update(const ros::Time& /*time*/,const ros::Duration& period) {// elapsed_time_ += period;// double delta_angle = M_PI / 16 * (1 - std::cos(M_PI / 5.0 * elapsed_time_.toSec())) * 0.2;// for (size_t i = 0; i < 7; ++i) {//   if (i == 4) {//     position_joint_handles_[i].setCommand(initial_pose_[i] - delta_angle);//   } else {//     position_joint_handles_[i].setCommand(initial_pose_[i] + delta_angle);//   }// }for (size_t i = 0; i < 7; ++i) {initial_pose_[i] = position_joint_handles_[i].getPosition();}for (size_t i = 0; i < 7; ++i) {position_joint_handles_[i].setCommand(initial_pose_[i] + joints_position_change[i]);joints_position_change[i] = 0.0;}
}}  // namespace franka_example_controllersPLUGINLIB_EXPORT_CLASS(franka_example_controllers::JointPositionExampleController,controller_interface::ControllerBase)

3、在package下新建scripts文件夹,新建 joint_position_keyboard.py 程序,如下:

#! /usr/bin/env python
#  技术交流 /服务v: L2622452304
import rospy
from std_msgs.msg import Float32MultiArray
import sys, select, termios, tty
from threading import Threadjoints_change = {'1':(0,0.01),'q':(0,-0.01),'2':(1,0.01),'w':(1,-0.01),'3':(2,0.01),'e':(2,-0.01),'4':(3, 0.01),'r':(3,-0.01),'5':(4, 0.01),'t':(4,-0.01),'6':(5, 0.01),'y':(5,-0.01),'7':(6, 0.01),'u':(6,-0.01),}
key = ''
rospy.init_node('keyboard_pub')
pub = rospy.Publisher('/keyboard', Float32MultiArray, queue_size=1)def getKey():global keytty.setraw(sys.stdin.fileno())rlist, _, _ = select.select([sys.stdin], [], [], 0.1)if rlist:key = sys.stdin.read(1)if key == 'z':print('Stop')exit(0)else:key = ''termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)def pub_command():global keyglobal pubkeyboard_command = Float32MultiArray()rate = rospy.Rate(100)while True:joints = [0.0,0.0,0.0,0.0,0.0,0.0,0.0]if key in joints_change.keys():joints[joints_change[key][0]] += joints_change[key][1]# print(joints)keyboard_command.data = jointspub.publish(keyboard_command)rate.sleep()if __name__ == '__main__':settings = termios.tcgetattr(sys.stdin)t = Thread(target=pub_command)t.start()try:while True:getKey()except rospy.ROSInterruptException:passtermios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)

实现原理

利用官方给的示例代码,稍作改动来驱动机械臂,然后用topic通信,把py获取的键盘控制信息发送到cpp内的机械臂控制循环中,实现关节运动控制。

使用

启动launch下的 joint_position_example_controller.launch,

<?xml version="1.0" ?>
<launch><include file="$(find franka_control)/launch/franka_control.launch" pass_all_args="true"/><arg name="arm_id" default="panda"/><rosparam command="load" file="$(find franka_example_controllers)/config/franka_example_controllers.yaml" subst_value="true" /><node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"  args="joint_position_example_controller"/><node pkg="rviz" type="rviz" output="screen" name="rviz" args="-d $(find franka_example_controllers)/launch/robot.rviz -f $(arg arm_id)_link0 --splash-screen $(find franka_visualization)/splash.png"/>
</launch>

也可实现键盘控制机械臂末端移动,但是代码为找到。后续可能继续更新在仿真中的实现。

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

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

相关文章

CRC(循环冗余校验码的校验方法)

5个关键点&#xff1a; 1.信息码&#xff1a;即给出要校验的二进制码 2.生成多项式&#xff1a;一般多项式会给&#xff0c;从最高位的指数位数就可以得到有几个校验码&#xff1b;如果没给多项式&#xff0c;肯定会给个多项式二进制码&#xff0c;根据它来推就行&#xff08;…

群体AI介绍

本文为介绍性文章&#xff0c;只是为了扩宽视野。 群体AI 1、简介 群体AI&#xff0c;也称为集体智能&#xff08;collective intelligence&#xff09;&#xff0c;是指通过联合多个智能体&#xff08;如人类、机器或其他智能系统&#xff09;的智能和资源来解决问题的一种方…

华为GaussDB数据库

Gauss数据库初识_高斯数据库_ygpGoogle的博客-CSDN博客 Redhat 7.6安装GaussDB_100_1.0.1详细攻略_gaussdb_100_1.0.1-database-redhat-64bit.tar.gz dow_博德1999的博客-CSDN博客 https://www.ngui.cc/el/3381579.html?actiononClick 初识GaussDB——GaussDB的发展历程、部…

Java基础(二十四):MySQL

文章目录 一、数据库&#xff08;创建、显示、删除、备份、恢复&#xff09;二、MySQL常用数据类型2.1 数值型&#xff08;整数&#xff09;2.2 数值型&#xff08;二进制bit&#xff09;2.3 数值型&#xff08;小数&#xff09;2.4 字符型2.5 日期类型 三、表结构的操作四、表…

3.docker仓库(Nexus、Harbor)的安装

本文目录 前言1.Aliyun 镜像仓库2.Nexus1.Nexus 私服搭建2.登录控制台3.配置nexus仓库4.配置nexus仓库地址为安全的镜像地址5.镜像推送至nexus仓库6.拉取nexus仓库镜像3.Harbor1.Docker Compose 安装2.Harbor安装3.配置Harbor仓库地址为安全的镜像地址4.创建项目5.镜像推送至Ha…

将函数实现放到CPP报“无法解析的外部符号...”,系VS Bug

发现一个现象&#xff0c;就是项目中有一个类&#xff0c;如果将函数实现全部放到头文件中&#xff0c;编译不报错&#xff0c;如果将函数实现放到CPP中则始终提示“无法解析的外部符号...”&#xff0c;考虑到放到头文件中能正常编译运行&#xff0c;显然这里不符合“无法解析…

软件设计师-UML基础教程

场景 针对UML1.5各种模型图的构成和功能进行说明。 UML概述 UML简介 UML (Unified Modeling Language)为面向对象软件设计提供统一的、标准的、可视化的建模语言。 适用于描述以用例为驱动&#xff0c;以体系结构为中心的软件设计的全过程。 UML的定义包括UML语义和UML表…

【CVPR2021】MVDNet论文阅读分析与总结

Challenge&#xff1a; 现有的目标检测器主要融合激光雷达和相机&#xff0c;通常提供丰富和冗余的视觉信息 利用最先进的成像雷达&#xff0c;其分辨率比RadarNet和LiRaNet中使用的分辨率要细得多&#xff0c;提出了一种有效的深度后期融合方法来结合雷达和激光雷达信号。 MV…

输电线路故障诊断(Python代码,逻辑回归、决策树、随机森林、XGBoost和支持向量机五种不同方法诊断)

效果视频&#xff1a;输电线路故障诊断&#xff08;Python代码&#xff0c;逻辑回归、决策树、随机森林、XGBoost和支持向量机五种不同方法诊断&#xff09;_哔哩哔哩_bilibili 1.数据 仿真平台 仿真模型分别获取单相接地故障、两相接地故障、两相间短路故障、三相接地故障、…

2023年浦东新区数字化安全风险智慧管控技能比武初赛-技能题一

目录 二、技能题 2.1 MD5===MD5 三、业*&&&务**&&联&&&*&&系 二、技能题 2.1 MD5===MD5

@Autowired、@Resource、@Qualifier

Autowired、Resource、Qualifier 1.Autowired和Resource 先看看Autowired和Resource的定义。 Target({ElementType.CONSTRUCTOR, ElementType.METHOD, ElementType.PARAMETER, ElementType.FIELD, ElementType.ANNOTATION_TYPE}) Retention(RetentionPolicy.RUNTIME) Docume…

Flutter动态化开发之Fair实战

一、背景 目前移动端应用的版本更新, 最常见的方式是定期发版,无论是安卓还是iOS,都需要提交新的安装包到应用市场进行审核。审核通过后,用户在应用市场进行App的下载更新。而动态化, 就是不依赖更新程序安装包, 就能动态实时更新页面的技术。 相比动态化技术,定期发版…

线性代数的本质(九)——二次型与合同

文章目录 二次型与合同二次型与标准型二次型的分类度量矩阵与合同 二次型与合同 二次型与标准型 Grant&#xff1a;二次型研究的是二次曲面在不同基下的坐标变换 由解析几何的知识&#xff0c;我们了解到二次函数的一次项和常数项只是对函数图像进行平移&#xff0c;并不会改变…

day40 设计模式、jdk8新特性

一、代理模式 为其他对象提供一种代理控制此对象的访问 若一个对象不适合直接引用另一个对象&#xff0c; 代理对象在客户端和目标对象之间起到中介作用 组成&#xff1a; 抽象角色&#xff1a;通过接口 抽象类 真实角色实现了哪些方法 代理角色&#xff1a;实现抽象角色…

k8s集群中部署服务之部署描述文件准备

微服务部署描述文件Deploy.yaml 一、各微服务创建部署描述文件 1.1 mall-auth-server --- apiVersion: apps/v1 kind: Deployment metadata:name: mall-auth-servernamespace: sangomalllabels:app: mall-auth-server spec:replicas: 1selector:matchLabels:app: mall-auth-s…

Python用若干列的数据多条件筛选、去除Excel数据并批量绘制直方图

本文介绍基于Python&#xff0c;读取Excel数据&#xff0c;以一列数据的值为标准&#xff0c;对这一列数据处于指定范围的所有行&#xff0c;再用其他几列数据数值&#xff0c;加以筛选与剔除&#xff1b;同时&#xff0c;对筛选与剔除前、后的数据分别绘制若干直方图&#xff…

设置伙伴(buddy)-给窗口控件增加快捷键

在官方教程或者很多qt程序中经常看到能使用全键盘操作软件&#xff0c;那么QT creator也支持了这一特性&#xff0c;就是使用设置伙伴来实现的。 我们可以在设计界面按照如下几步实现&#xff1a; 先放置label 再放置一个lineEdit控件。 这个时候我们就可以开始伙伴绑定的步骤…

clip模型

文章目录 前言1 如何实现&#xff1f;1.概论2 训练3.有什么用&#xff1f;1.如何进行推理 4 通过代码来玩clip模型 前言 本文专门开一节写SD原理相关的内容&#xff0c;在看之前&#xff0c;可以同步关注&#xff1a; stable diffusion实践操作 CLIP&#xff0c;OPENAI 的产品…

JVM 虚拟机 ----> Java 类加载机制

文章目录 JVM 虚拟机 ----> Java 类加载机制一、概述二、类的生命周期1、类加载过程&#xff08;Loading&#xff09;&#xff08;1&#xff09;加载&#xff08;2&#xff09;验证&#xff08;3&#xff09;准备&#xff08;4&#xff09;解析&#xff08;5&#xff09;初始…

Spring Boot - Junit4 / Junit5 / Spring Boot / IDEA 关系梳理

文章目录 PreJunit4 / Junit5 / Spring Boot / IDEAIDEA版本Spring-Boot-Older-Release-NotesSpringBootTest 起源 & Spring-Boot-1.4-Release-Notes2.0.0.RELEASE ----- 2.0.9.RELEASE2.1.0.RELEASE ----- 2.1.18.RELEASE2.2.0.RELEASE ~ 2.2.13.RELEASE2.3.0.RELEASE ~ 2…