Unable to set solver_type in launch file via kinematics.yaml or param/rosparam for trac_ik [closed]
To Whom It May Concern,
After installing trac-ik-kinematics-plugin, I changed the kinematics.yaml to use trac_ik vs ur_kinematics and my Clearpath Husky with UR5 arm successfully planned several IK problems.
However, when I use the code below:
# Give the node a name
rospy.init_node("drill_prediction", anonymous=False)
# Initialize the move_group API
moveit_commander.roscpp_initialize(sys.argv)
# Initialize the move group for the arm
ur5_arm = moveit_commander.MoveGroupCommander("ur5_arm")
# Get the name of the end-effector link
end_effector_link = ur5_arm.get_end_effector_link()
# Set the reference frame for pose targets
reference_frame = "/base_link"
# Set the arm reference frame accordingly
ur5_arm.set_pose_reference_frame(reference_frame)
# Allow replanning to increase the odds of a solution
ur5_arm.allow_replanning(True)
# Allow some leeway in position (meters) and orientation (radians)
ur5_arm.set_goal_position_tolerance(0.01)
ur5_arm.set_goal_orientation_tolerance(0.05)
#Move the end effecor to the x , y, z positon
#Set the target pose in the base_link frame
target_pose = PoseStamped()
target_pose.header.frame_id = reference_frame
target_pose.header.stamp = rospy.Time.now()
target_pose.pose.position.x = 1.0 #hole_pose.position.x
target_pose.pose.position.y = .1 #hole_pose.position.y
target_pose.pose.position.z = .7 #hole_pose.position.z
target_pose.pose.orientation.x = 0 #hole_pose.orientation.x
target_pose.pose.orientation.y = 0 #hole_pose.orientation.y
target_pose.pose.orientation.z = 0 #hole_pose.orientation.z
target_pose.pose.orientation.w = 1 #hole_pose.orientation.w
# Set the start state to the current state
ur5_arm.set_start_state_to_current_state()
# Set the goal pose of the end effector to the stored pose
ur5_arm.set_pose_target(target_pose, end_effector_link)
# Plan the trajectory to the goal
traj = ur5_arm.plan()
# Execute the planned trajectory
ur5_arm.execute(traj)
# Pause for a second
rospy.sleep(1)
# Shut down MoveIt cleanly
moveit_commander.roscpp_shutdown()
# Exit MoveIt
moveit_commander.os._exit(0)
However, my nodes fails to set the params as I have set them in my kinematics.yaml
ur5_arm:
kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
kinematics_solver_timeout: 0.05
solve_type: Manipulation1
and returns this
[ INFO] [1467410538.629341568, 298.510000000]: Looking in private handle: /move_group_commander_wrappers_1467410538042921053 for param name: ur5_arm/position_only_ik
[ INFO] [1467410538.629825732, 298.510000000]: Looking in private handle: /move_group_commander_wrappers_1467410538042921053 for param name: ur5_arm/solve_type
[ INFO] [1467410538.630190163, 298.510000000]: Using solve type Speed
Despite my launch file below including every way I can think of to set these parameters.
<launch>
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
<include file="$(find husky_ur5_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<node name="drill_predition" pkg="ccam_arm_nav" type="drill_prediction.py" output="screen">
<rosparam command="load" file="$(find husky_ur5_moveit_config)/config/kinematics.yaml"/>
<param name="arm_prefix" value="ur5_arm_"/>
<param name="move_group/ur5_arm/solve_type" value="Manipulation1"/>
<param name="move_group/ur5_arm/kinematics_solver_timeout" value="0.05"/>
<param name="ur5_arm/solve_type" value="Manipulation1"/>
<param name="ur5_arm/kinematics_solver_timeout" value="0.05"/>
<param name="solve_type" value="Manipulation1"/>
<param name="kinematics_solver_timeout" value="0.05"/>
<rosparam>
move_group/ur5_arm/solve_type: 'Manipulation1'
move_group/ur5_arm/kinematics_solver_timeout: 0.05
ur5_arm/solve_type: 'Manipulation1'
ur5_arm/kinematics_solver_timeout: 0.05
solve_type: 'Manipulation1'
kinematics_solver_timeout: 0.05
</rosparam>
</node>
</launch>
However, move_group.launch and moveit_rviz.launch seem to set them correctly. Accuracy rather than speed is my desire; so, I like to test out the other solver_types, such as Manipulation1 ...