首先從Moveit官方的Tutorial開始。使用C++撰寫機器手臂的控制。教材依據Move Group C++ Interface。
本篇描述使用Move Group去撰寫。Move Group是Moveit中的一個基礎的class,根據ROS文件。整體來講功能分類:
// 用string,指定手臂名稱,這名子來自RViz內Planning Group
static const std::string PLANNING_GROUP = "panda_arm";
// 宣告一個MoveGroupInterface,也就是等等來執行運動學、抓取工件等等
moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);
// 建立場景,在這環境產生障礙物
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
// 指標指向getJointModelGroup
const robot_state::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
接著visual_tools相關的是在介面上畫圖寫字,ROS_INFO_NAMED則是在終端機上寫字,這部分可直接參考上面的參考連結1,這邊不做解釋。
手臂的第一個動作使用setPoseTarget這指令做移動,給一組座標位置作移動。setPoseTarget有三種型態,本範例放入Pose,Pose內結構說明
geometry_msgs::Pose target_pose1; // 宣告pose
target_pose1.orientation.w = 1.0; // 四元數旋轉
target_pose1.position.x = 0.28; // 設定XYZ座標
target_pose1.position.y = -0.2;
target_pose1.position.z = 0.5;
move_group.setPoseTarget(target_pose1); // 執行,此時手臂開始作動
orientation這個地方使用四元數,四元數的運算公式,後續進階篇在解釋。
第二個動作是用setJoint,被關節角度移動手臂(正向運動學),只需要vector給角度。
moveit::core::RobotStatePtr current_state = move_group.getCurrentState(); //
std::vector<double> joint_group_positions; // 定義一組double
current_state->copyJointGroupPositions(joint_model_group, joint_group_positions);// 當前位置給入joint_group_positions
joint_group_positions[0] = -1.0; // 給角度,單位:radians
move_group.setJointValueTarget(joint_group_positions); // 執行
以上是給予角度讓手臂移動,可以自行定義角度,不一定要使用Current State,可以自己定義角度值。
第三個動作,給一組座標位置作移動(逆向運動學)但是給予限制條件,會用到第一組動作的指令
moveit_msgs::OrientationConstraint ocm; // 宣告
ocm.link_name = "panda_link7"; // 要被限制的座標
ocm.header.frame_id = "panda_link0"; // 要限制的原始座標
ocm.orientation.w = 1.0; // 開始定義方向、xyz誤差量
ocm.absolute_x_axis_tolerance = 0.1;
ocm.absolute_y_axis_tolerance = 0.1;
ocm.absolute_z_axis_tolerance = 0.1;
ocm.weight = 1.0;
moveit_msgs::Constraints test_constraints; // 宣告
test_constraints.orientation_constraints.push_back(ocm); // 放入剛剛的限制條件,可以放入多組
move_group.setPathConstraints(test_constraints); // 放入限制條件進入這個group內
robot_state::RobotState start_state(*move_group.getCurrentState());
geometry_msgs::Pose start_pose2;
start_pose2.orientation.w = 1.0;
start_pose2.position.x = 0.55;
start_pose2.position.y = -0.05;
start_pose2.position.z = 0.8;
start_state.setFromIK(joint_model_group, start_pose2); // 逆向運動學求解,此時的joint_model_group會被計算成start_pose2的解答
move_group.setStartState(start_state); // 設定起始位置,也就是說可以不用現在手臂的位置做起點
move_group.setPoseTarget(target_pose1); // 有這指令才能畫出Path,做出路徑規劃
move_group.setPlanningTime(10.0);
這個範例,是在示範Constraints這樣的運動拘束,也就是說可以用此功能做出orientation指向某方向的移動。
接著使用到setStartState定義一個起始點,需要這起始點是因為現在手臂的位置,並不好無法符合拘束條件,所以定義一個起點。
因為給的是座標所以使用setFromIK,再用setStartState寫入這個位置,之後的setPoseTarget,就會做出:start_pose2到target_pose1,然後符合拘束條件的Path。(後續在運動學的文章探討)
第四個動作是直線移動,與第一個範例一樣給座標,但差別是移動的路徑是直線。
geometry_msgs::Pose target_pose3 = move_group.getCurrentPose().pose; // 宣告一個pose,取出現在手臂的pose
std::vector<geometry_msgs::Pose> waypoints; // 塞入pose用的
waypoints.push_back(target_pose3);
target_pose3.position.z -= 0.2; // 修改pose位置
waypoints.push_back(target_pose3);
target_pose3.position.y -= 0.2;
waypoints.push_back(target_pose3);
target_pose3.position.z += 0.2;
target_pose3.position.y += 0.2;
target_pose3.position.x -= 0.2;
waypoints.push_back(target_pose3);
move_group.setMaxVelocityScalingFactor(0.1); // 設定最大速度
moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.0;
const double eef_step = 0.01;
double fraction = move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
target_pose3這個座標是從getCurrentPose取出來的,所以這範例手臂的移動從當前的位置開始做直線移動到watpoints中的點。要注意的是這功能的pose是可以改變的,也就是說第一點可以設定pose朝下,其餘的點朝其他方向,而手臂移動路徑是直線,所以pose可以自行定義但要注意奇異點。
這個範例的畫圖功能是亂畫的,只是把上述三個點連接起來,並不是依據trajectory畫圖,至於這個trajectory可以使用move_group.execute(trajectory);去執行所產生的路徑。
第五個範例是手臂避障,在Rviz空間中產生障礙物,然後手臂會避開障礙物抵達target。逐行程式說明可參考開頭的參考一這裡不贅述。這裡提供額外的說明。
collision_objects.push_back(collision_object) // 避障運算是依據這一行
planning_scene_interface.addCollisionObjects(collision_objects); // 將障礙物畫在圖上
Kinetic版本避障的範例比較簡陋,最新版本的程式碼比較完整,留到下回合進接篇說明。
結論:這範例示範了五個手臂的動作,但是都是單一動作不是連貫的動作,要將以上的組合成一套完整的動作,還需要嘗試。整體來說第一、二、四範例比較實用比較適合應用在手臂上,其餘的需要了解moveit本身的運算才能熟悉。