1、MOVO安裝教程
MOVO開發硬件需求
官方只支持Ubuntu 14.04 Trusty, x64 platform (core i5, core i7), 8GB RAM。
軟件安裝
您需要安裝幾個開發包才能在MOVO上進行開發。 一些包裝屬於Kinova外部開發包,其他的是Kinova專用開發包。 如果您在安裝Kinova開發包時遇到任何障礙,請在此處報告問題。 對於任何專門針對外部庫的問題,這些庫的支持團隊可能是獲得修復的最佳選擇。 但是,我們很樂意回答您的任何問題,並提供有關您使用MOVO開發的任何問題的幫助。 本節將指導您完成安裝過程。
-有兩種安裝的方式:自動/手動
-
自動安裝腳本使用方式:創建工作區並克隆kinova-movo庫後,運行交互式bash腳本* setup_remote_pc *以自動執行安裝。推薦採用自動方式。
-
手動安裝方式具體見此處。
連接到MOVO平臺
- 通過無線或有限兩種方式連接到MOVO平臺。
無線wifi(wifi名: MoVoWifi 密碼: Welcome00) - 通過SSH登陸到MOVO,
ssh [email protected]
,登陸密碼Welcome00
。 - 若要將手柄連接到遠程開發者電腦上使用,打開終端進行以下操作:
cd ~/movo_ws
sws # alias sws='source ./devel/setup.bash' defined in .bashrc
roslaunch movo_remote_teleop movo_remote_teleop.launch
- 若要將手柄插在MOVO上使用,在遠程開發者電腦上SSH登陸到MOVO後,執行以下操作:
cd ~/movo_ws
sws # alias sws='source ./devel/setup.bash' defined in .bashrc
roslaunch movo_remote_teleop movo_remote_teleop.launch
2、MOVO機器人的基本使用
官方提供了以下功能:
- 建立遠程開發者電腦與MOVO的連接
- 檢測遠程連接狀態
- 使用真實機器人重新配置參數
- 查找Kinect序列號
- 爲6自由度機械臂配置MOVO
- -更新MOVO代碼
- -診斷MOVO啓動問題
- 樣例DEMO
- 使用真實機器人建圖
- 使用真實機器人在rviz中導航地圖
- 使用直接操作模式控制真實機器人
- 使用輔助操作模式控制真實機器人
- 使用仿真機器人建圖
- 使用仿真機器人定位
3、製作倒水DEMO
以下爲主程序
// movo_moveit_uoperbody.cpp
#include <moveit/move_group_interface/move_group.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit_msgs/DisplayRobotState.h>
#include <moveit_msgs/DisplayTrajectory.h>
#include <moveit_msgs/AttachedCollisionObject.h>
#include <moveit_msgs/CollisionObject.h>
#include <control_msgs/GripperCommandActionGoal.h>
//grasp
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <control_msgs/GripperCommandAction.h>
#include <control_msgs/GripperCommandGoal.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "movo_moveit");
ros::NodeHandle node_handle;
ros::AsyncSpinner spinner(1);
spinner.start();
//action grasp
actionlib::SimpleActionClient<control_msgs::GripperCommandAction> acr("/movo/right_gripper_controller/gripper_cmd", true);
ROS_INFO("Waiting for the gripper action server");
acr.waitForServer(ros::Duration(3));
ROS_INFO("Connected to move base server");
control_msgs::GripperCommandGoal grigoal_right;
actionlib::SimpleActionClient<control_msgs::GripperCommandAction> acl("/movo/left_gripper_controller/gripper_cmd", true);
// Wait 60 seconds for the action server to become available
ROS_INFO("Waiting for the gripper action server");
acl.waitForServer(ros::Duration(3));
ROS_INFO("Connected to move base server");
control_msgs::GripperCommandGoal grigoal_left;
moveit::planning_interface::MoveGroup group("upper_body");
moveit::planning_interface::MoveGroup l_group("left_arm");
moveit::planning_interface::MoveGroup r_group("right_arm");
group.setNamedTarget("homed_2");
moveit::planning_interface::MoveGroup::Plan upperbody_plan;
bool success_upper = group.plan(upperbody_plan);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_upper)
group.execute(upperbody_plan);
group.setNamedTarget("plan_grasp");
moveit::planning_interface::MoveGroup::Plan upperbody_plan_1;
bool success_upper_1 = group.plan(upperbody_plan_1);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_upper_1)
{
group.execute(upperbody_plan_1);
}
//opengrasp
grigoal_right.command.position = 0.16;
ROS_INFO("Sending goal");
acr.sendGoal(grigoal_right);
acr.waitForResult();
if (acr.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
grigoal_left.command.position = 0.16;
ROS_INFO("Sending goal");
acl.sendGoal(grigoal_left);
acl.waitForResult();
if (acl.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
sleep(3);
//youbi_1_2_3
r_group.setNamedTarget("right_grasp1");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_1;
bool success_right_grasp_1 = r_group.plan(right_grasp_plan_1);
ROS_INFO("Visualizing plan1 (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_1)
{
sleep(1);
r_group.execute(right_grasp_plan_1);
}
r_group.setNamedTarget("right_grasp2");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_2;
bool success_right_grasp_2 = r_group.plan(right_grasp_plan_2);
ROS_INFO("Visualizing plan2 (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_2)
{
sleep(1);
r_group.execute(right_grasp_plan_2);
}
//closegrasp_right
grigoal_right.command.position = 0.03;
ROS_INFO("Sending goal");
acr.sendGoal(grigoal_right);
acr.waitForResult();
if (acr.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
r_group.setNamedTarget("right_grasp3");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_3;
bool success_right_grasp_3 = r_group.plan(right_grasp_plan_3);
ROS_INFO("Visualizing plan3 (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_3)
{
sleep(1);
r_group.execute(right_grasp_plan_3);
}
//zuobi1-2-3
l_group.setNamedTarget("left_grasp1");
moveit::planning_interface::MoveGroup::Plan left_grasp_plan_1;
bool success_left_grasp_1 = l_group.plan(left_grasp_plan_1);
ROS_INFO("Visualizing plan1_1 (pose goal) %s",success_upper?"":"FAILED");
if(success_left_grasp_1)
{
sleep(1);
l_group.execute(left_grasp_plan_1);
}
l_group.setNamedTarget("left_grasp2");
moveit::planning_interface::MoveGroup::Plan left_grasp_plan_2;
bool success_left_grasp_2 = l_group.plan(left_grasp_plan_2);
ROS_INFO("Visualizing plan2_1 (pose goal) %s",success_upper?"":"FAILED");
if(success_left_grasp_2)
{
sleep(1);
l_group.execute(left_grasp_plan_2);
}
//closegrasp_left
grigoal_left.command.position = 0.03;
ROS_INFO("Sending goal");
acl.sendGoal(grigoal_left);
acl.waitForResult();
if (acl.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
l_group.setNamedTarget("left_grasp3");
moveit::planning_interface::MoveGroup::Plan left_grasp_plan_3;
bool success_left_grasp_3 = l_group.plan(left_grasp_plan_3);
ROS_INFO("Visualizing plan3_1 (pose goal) %s",success_upper?"":"FAILED");
if(success_left_grasp_3)
{
sleep(1);
l_group.execute(left_grasp_plan_3);
}
sleep(1);
//youbi-4
r_group.setNamedTarget("right_grasp4");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_4;
bool success_right_grasp_4 = r_group.plan(right_grasp_plan_4);
ROS_INFO("Visualizing plan4 (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_4)
{
sleep(1);
r_group.execute(right_grasp_plan_4);
}
sleep(3);
//youbi-3
r_group.setNamedTarget("right_grasp3");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_3_1;
bool success_right_grasp_3_1 = r_group.plan(right_grasp_plan_3_1);
ROS_INFO("Visualizing plan3 (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_3_1)
{
sleep(1);
r_group.execute(right_grasp_plan_3_1);
}
//youbi-2
r_group.setNamedTarget("right_grasp2");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_2_1;
bool success_right_grasp_2_1 = r_group.plan(right_grasp_plan_2_1);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_2_1)
{
sleep(1);
r_group.execute(right_grasp_plan_2_1);
}
//opengrasp-right
grigoal_right.command.position = 0.16;
ROS_INFO("Sending goal");
acr.sendGoal(grigoal_right);
acr.waitForResult();
if (acr.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//opengrasp
//youbi-1
r_group.setNamedTarget("right_grasp1");
moveit::planning_interface::MoveGroup::Plan right_grasp_plan_1_1;
bool success_right_grasp_1_1 = r_group.plan(right_grasp_plan_1_1);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_right_grasp_1_1)
{
sleep(1);
r_group.execute(right_grasp_plan_1_1);
}
//zoubi-2
l_group.setNamedTarget("left_grasp2");
moveit::planning_interface::MoveGroup::Plan left_grasp_plan_2_1;
bool success_left_grasp_2_1 = l_group.plan(left_grasp_plan_2_1);
ROS_INFO("Visualizing plan1_1 (pose goal) %s",success_upper?"":"FAILED");
if(success_left_grasp_2_1)
{
sleep(1);
l_group.execute(left_grasp_plan_2_1);
}
//opengrasp-left
grigoal_left.command.position = 0.16;
ROS_INFO("Sending goal");
acl.sendGoal(grigoal_left);
acl.waitForResult();
if (acl.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
//zoubi-1
l_group.setNamedTarget("left_grasp1");
moveit::planning_interface::MoveGroup::Plan left_grasp_plan_1_1;
bool success_left_grasp_1_1 = l_group.plan(left_grasp_plan_1_1);
ROS_INFO("Visualizing plan1_1 (pose goal) %s",success_upper?"":"FAILED");
if(success_left_grasp_1_1)
{
sleep(1);
l_group.execute(left_grasp_plan_1_1);
}
//dual-2
group.setNamedTarget("plan_grasp");
moveit::planning_interface::MoveGroup::Plan upperbody_plan_1_1;
bool success_upper_1_1 = group.plan(upperbody_plan_1_1);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_upper_1_1)
{
group.execute(upperbody_plan_1_1);
}
sleep(4);
//closegripper
//closegrasp_right
grigoal_right.command.position = 0.03;
ROS_INFO("Sending goal");
acr.sendGoal(grigoal_right);
acr.waitForResult();
if (acr.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
//closegrasp_left
grigoal_left.command.position = 0.03;
ROS_INFO("Sending goal");
acl.sendGoal(grigoal_left);
acl.waitForResult();
if (acl.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
ROS_INFO("You have reached the goal!");
else
ROS_INFO("The base failed for some reason");
//grasp
//dual-1
group.setNamedTarget("homed_2");
moveit::planning_interface::MoveGroup::Plan upperbody_plan_0_1;
bool success_upper_0_1 = group.plan(upperbody_plan_0_1);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_upper_0_1)
group.execute(upperbody_plan_0_1);
sleep(2);
//dual-0
group.setNamedTarget("tucked");
moveit::planning_interface::MoveGroup::Plan upperbody_plan_0;
bool success_upper_0 = group.plan(upperbody_plan_0);
ROS_INFO("Visualizing plan (pose goal) %s",success_upper?"":"FAILED");
if(success_upper_0)
group.execute(upperbody_plan_0);
ros::shutdown();
return 0;
}
其中,我們通過在moveit配置中預存了很多的位姿如:right_grasp1實現精準控制。
通過使用此語句設定目標併發送:r_group.setNamedTarget(“right_grasp1”);
位姿預存在/kinova-movo/movo_moveit_config/config/movo_kg2.srdf文件中。格式如下:
<group_state name="plan_grasp" group="upper_body">
<joint name="right_elbow_joint" value="2.28" />
<joint name="right_shoulder_lift_joint" value="2.17" />
<joint name="right_shoulder_pan_joint" value="-2.56" />
<joint name="right_wrist_1_joint" value="-0.09" />
<joint name="right_wrist_2_joint" value="0.15" />
<joint name="right_wrist_3_joint" value="1.06" />
<joint name="left_elbow_joint" value="-2.28" />
<joint name="left_shoulder_lift_joint" value="-2.17" />
<joint name="left_shoulder_pan_joint" value="2.56" />
<joint name="left_wrist_1_joint" value="0.09" />
<joint name="left_wrist_2_joint" value="-0.15" />
<joint name="left_wrist_3_joint" value="2.06" />
<joint name="linear_joint" value="0.45" />
<joint name="pan_joint" value="0.0" />
<joint name="tilt_joint" value="0.0" />
</group_state>
具體學習可以參照此處:
通過c++接口調用Moveit進行編程