文章目录
- 1、安装等基本操作
-
-
- 1.1 安装软件包
-
- Ubuntu 16.04 + ROS Kinetic
- Ubuntu 14.04 + ROS Indigo
- 1.2 使用仿真模型
- 1.3 使用真实的Cute机器人
-
- 2、多机器人启动文件配置
- 3、机械臂控制海草舞DEMO
1、安装等基本操作
本文件夹中包含了多个为Cute机器人提供ROS支持的软件包。推荐的运行环境为 Ubuntu 16.04 + ROS Kinetic 或 Ubuntu 14.04 + ROS Indigo,其他环境下的运行情况没有测试过。
1.1 安装软件包
Ubuntu 16.04 + ROS Kinetic
安装一些重要的依赖包
$ sudo apt-get install ros-kinetic-dynamixel-motor ros-kinetic-gazebo-ros-control ros-kinetic-ros-control ros-kinetic-ros-controllers
安装和升级MoveIt!, 注意因为MoveIt!最新版进行了很多的优化,如果你已经安装了MoveIt!, 也请一定按照以下方法升级到最新版。
安装/升级MoveIt!:
$ sudo apt-get update
$ sudo apt-get install ros-kinetic-moveit
安装本软件包
首先创建catkin工作空间 (教程)。 然后将本文件夹克隆到src/目录下,之后用catkin_make来编译。
假设你的工作空间是~/catkin_ws,你需要运行的命令如下:
$ cd ~/catkin_ws/src
$ git clone -b kinetic-devel https://github.com/hans-robot/cute_robot.git
$ cd ..
$ catkin_make
$ source devel/setup.bash
Ubuntu 14.04 + ROS Indigo
安装一些重要的依赖包
$ sudo apt-get install ros-indigo-dynamixel-motor ros-indigo-gazebo-ros-control ros-indigo-ros-control ros-indigo-ros-controllers
安装和升级MoveIt!, 注意因为MoveIt!最新版进行了很多的优化,如果你已经安装了MoveIt!, 也请一定按照以下方法升级到最新版。
安装/升级MoveIt!:
$ sudo apt-get update
$ sudo apt-get install ros-indigo-moveit
$ sudo apt-get install ros-indigo-moveit-full-pr2
$ sudo apt-get install ros-indigo-moveit-kinematics
$ sudo apt-get install ros-indigo-moveit-ros-move-group
1.2 使用仿真模型
用Gazebo仿真请运行:
$ roslaunch cute_model gazebo.launch
运行MoveIt!模块和RViz界面:
$ roslaunch cute_moveit_config moveit_planning_execution.launch
关于MoveIt!的使用方法可以参考docs/moveit_plugin_tutorial.md
Tips:
每次规划路径时,都要设置初始位置为当前位置。
打开以下程序用键盘操作模型:
$ rosrun cute_teleop cute_teleop_keyboard
运行以下程序开启手柄遥控功能:
$ roslaunch cute_moveit_config joystick_control.launch
关于手柄遥控的使用方法可以参考下面的链接:
http://docs.ros.org/indigo/api/moveit_tutorials/html/doc/ros_visualization/joystick.html
Tips:
1、In the Motion Planning plugin of Rviz, enable “Allow External Comm.” checkbox in the “Planning” tab.
2、Add “Pose” to rviz Displays and subscribe to /joy_pose in order to see the output from joystick. Note that only planning groups that have IK solvers for all their End Effector parent groups will work.
更多关于API的信息请看docs/API_description.md
1.3 使用真实的Cute机器人
将Cute通过USB线连接到电脑。用以下命令可以查到当前电脑连接的USB设备的编号:
$ ls /dev/ttyUSB*
如果有多个设备的话,可以先在不连Cute的情况下确定其他设备的编号,再插入Cute连接线,这样新增加的设备编号就是Cute的了。本软件包默认的编号是/dev/ttyUSB0 。假如当前编号不是0的话,请对cute_bringup/launch/cute_bringup.launch的相应部分进行修改。
port_name: "/dev/ttyUSB0"
根据Cute所搭载的舵机型号对启动文件的相应部分进行修改。
cute_bringup/launch/cute_bringup.launch:
<!-- There are 3 options for servo: dynamixel, xqtor_0, xqtor_1 -->
<!-- xqtor_0: the early version of the xQtor servo before 2017-->
<!-- xqtor_1: the new version of the xQtor servo -->
<arg name="servo" default="xqtor_1"/>
现假设设备编号是/dev/ttyUSB0,运行以下指令来启动驱动:
$ sudo chmod 777 /dev/ttyUSB0
$ roslaunch cute_bringup cute_bringup.launch
令机械臂回到起始位姿:
$ rosservice call /cute_go_home "data: true"
在上行命令中,“data: false” 和 ”data: true” 的效果是一样的。
运行MoveIt!模块和RViz界面:
$ roslaunch cute_moveit_config moveit_planning_execution.launch
关于MoveIt!的使用方法可以参考docs/moveit_plugin_tutorial.md
Tips:
每次规划路径时,都要设置初始位置为当前位置。
如果你此时不想运行RViz界面,请用以下命令:
$ roslaunch cute_moveit_config moveit_planning_execution.launch display:=false
打开以下程序用键盘操作机械臂:
$ rosrun cute_teleop cute_teleop_keyboard
运行以下程序开启手柄遥控功能:
$ roslaunch cute_moveit_config joystick_control.launch
关于手柄遥控的使用方法可以参考下面的链接:
http://docs.ros.org/indigo/api/moveit_tutorials/html/doc/ros_visualization/joystick.html
Tips:
1、In the Motion Planning plugin of Rviz, enable “Allow External Comm.” checkbox in the “Planning” tab.
2、Add “Pose” to rviz Displays and subscribe to /joy_pose in order to see the output from joystick. Note that only planning groups that have IK solvers for all their End Effector parent groups will work.
在关闭机械臂电源前,先运行以下命令可让机械臂提前去使能,此时请用手保护好机械臂,以防它失力后掉下来。
$ rosservice call /cute_torque_enable "data: false"
注意,在上行命令中,“data: false” 和 ”data: true” 的效果是不一样的。“data: false”可让机械臂去使能。与之相反,“data: true”可让机械臂使能。
控制夹爪前也需将其使能
$ rosservice call /claw_controller/torque_enable "torque_enable: true"
更多关于API的信息请看docs/API_description.md
以上参考自:Github:hans-robot/cute_robot
Ros-Wiki-Hans-Cute
2、多机器人启动文件配置
代码参考此处
多机器人在ros下的launch启动文件配置
3、机械臂控制海草舞DEMO
基于Moveit对机械臂进行规划,不会Moveit的看这里通过c++接口调用Moveit进行编程
通过使用rostopic list读取话题列表。
使用rostopic echo /topic 读取对应的/topic的消息内容。
使用rosmsg show /messagename 读取/messagename的消息格式 。
以下为此机器人跳舞的代码。
demo1.cpp
/*
* demo1.cpp
*
* Created on: 2019.1.26
* Author: wxw
* Author: wlg
*/
#include <termios.h>
#include <signal.h>
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <poll.h>
#include <vector>
#include <boost/thread/thread.hpp>
#include <ros/ros.h>
#include <tf/tf.h>
#include <moveit_msgs/GetPositionFK.h>
#include <moveit_msgs/GetPositionIK.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Pose.h>
#include <urdf/model.h>
#include <std_msgs/Float64.h>
#include <sensor_msgs/JointState.h>
#include <actionlib/client/simple_action_client.h>
#include <control_msgs/FollowJointTrajectoryAction.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "send_goals_node");
ros::Duration dur(1);
actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> ac("cute_arm_controller/follow_joint_trajectory", true);
// Wait 60 seconds for the action server to become available
ROS_INFO("Waiting for the gripper action server");
ac.waitForServer(ros::Duration(3));
ROS_INFO("Connected to move base server");
// Send a goal to move_base1
control_msgs::FollowJointTrajectoryGoal goal;
int steps_num=17;
float Goalpoint[steps_num][7]={
{0.0, 0.006135923151542565, 0.0, 1.603009923340495, 0.0015339807878856412, 0.007669903939428206, 0.0},
{0.0, 0.0, 0.0030679615757712823, 1.603009923340495, 0.1119805975156518, -1.1397477253990314, 0.0},
{0.0, 0.0015339807878856412, 0.0030679615757712823, 1.5953400194010667, 0.1119805975156518, 0.8084078752157329, 0.0},
{0.0, 0.0, 0.0030679615757712823, 1.603009923340495, 0.1119805975156518, -1.1397477253990314, 0.0},
{0.0, 0.0015339807878856412, 0.0030679615757712823, 1.5953400194010667, 0.1119805975156518, 0.8084078752157329, 0.0},
{0.0, 0.0, 0.0030679615757712823, 1.603009923340495, 0.1119805975156518, -1.1397477253990314, 0.0},
{0.0, 0.0015339807878856412, 0.0030679615757712823, 1.5953400194010667, 0.1119805975156518, 0.8084078752157329, 0.0},
{0.0, 0.0, 0.0030679615757712823, 1.603009923340495, 0.1119805975156518, -1.1397477253990314, 0.0},
{0.0, 0.0015339807878856412, 0.0030679615757712823, 1.5953400194010667, 0.1119805975156518, 0.8084078752157329, 0.0},
{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0},
{0.0, 0.43718452454740775, 0.02454369260617026, -0.6872233929727672, 0.007669903939428206, 0.6166602767300278, 0.010737865515199488},
{0.0, -0.2807184841830723, 0.032213596545598466, 0.6902913545485385, 0.010737865515199488, -0.9035146840646426, 0.018407769454627694},
{0.0, 0.43718452454740775, 0.02454369260617026, -0.6872233929727672, 0.007669903939428206, 0.6166602767300278, 0.010737865515199488},
{0.0, -0.2807184841830723, 0.032213596545598466, 0.6902913545485385, 0.010737865515199488, -0.9035146840646426, 0.018407769454627694},
{0.0, 0.43718452454740775, 0.02454369260617026, -0.6872233929727672, 0.007669903939428206, 0.6166602767300278, 0.010737865515199488},
{0.0, -0.2807184841830723, 0.032213596545598466, 0.6902913545485385, 0.010737865515199488, -0.9035146840646426, 0.018407769454627694},
{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0},
};
goal.trajectory.joint_names.push_back("joint1");
goal.trajectory.joint_names.push_back("joint2");
goal.trajectory.joint_names.push_back("joint3");
goal.trajectory.joint_names.push_back("joint4");
goal.trajectory.joint_names.push_back("joint5");
goal.trajectory.joint_names.push_back("joint6");
goal.trajectory.joint_names.push_back("joint7");
goal.trajectory.points.resize(steps_num);
for(int i=0; i<steps_num; i++)
{
for(int joint=0;joint<7;joint++)
{
ROS_INFO("test!!!!!!!!!!!!!!!!!!!");
goal.trajectory.points[i].positions.resize(7);
goal.trajectory.points[i].time_from_start=dur.operator *(i+1);
goal.trajectory.points[i].positions[joint]=Goalpoint[i][joint];
}
ROS_INFO("Sending goal");
ac.sendGoal(goal);
// Wait for the action to return
ac.waitForResult();
if (ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
}
return 0;
}
CmakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(cute_demo)
find_package(catkin REQUIRED COMPONENTS
actionlib
control_msgs
roscpp
rospy
std_msgs
urdf
)
catkin_package(
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(demo1 src/demo1.cpp)
add_dependencies(demo1 ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(demo1 ${catkin_LIBRARIES})
package.xml
<?xml version="1.0"?>
<package>
<name>cute_demo</name>
<version>1.0.0</version>
<description>The cute_demo package</description>
<maintainer email="565346370@qq.com">wxw</maintainer>
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>actionlib</build_depend>
<build_depend>control_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>actionlib</run_depend>
<run_depend>control_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
</package>