Skip to content

Commit

Permalink
added image to README
Browse files Browse the repository at this point in the history
  • Loading branch information
mihyr committed Mar 19, 2021
1 parent affc620 commit c520a08
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 11 deletions.
Binary file added baxter_control/Blankdiagram.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
2 changes: 2 additions & 0 deletions baxter_control/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ Args | Default | Description
`joystick` | `xbox` | set controller (xbox | Logitech | PS4)
`dev` | `/dev/input/js0` | path to controller
# Workflow
![rqt](Blankdiagram.png)
# Services available
- home: move left and right arm to predefined `left_neutral` and `right_neutral` position respectively
```
Expand Down
6 changes: 3 additions & 3 deletions baxter_control/config/global_params.yaml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#Note: This parameters are meant for trajectory node
Fr : 200 #frequency
x_waypoints : [0.8, 0.9, 0.9, 1] #x coordinates for end effector
y_waypoints : [0.6, 0.62, -0.20, -0.2] #y coordinates for end effector
z_waypoints : [-0.06, 0.13, 0.03, -0.10] #z coordinates for end effector
x_waypoints : [0, 0, 0, 0] #x coordinates for end effector
y_waypoints : [-0.2, 0.2, -0.50, 0.2] #y coordinates for end effector
z_waypoints : [-0.18, 0.2, -0.18, 0.2] #z coordinates for end effector
time : [] #corresponding time for coordinates of end effector


Expand Down
15 changes: 7 additions & 8 deletions baxter_control/nodes/trajectory
Original file line number Diff line number Diff line change
Expand Up @@ -71,15 +71,15 @@ def main():
print(right_current_pose)

#Set moveit params
left_arm_moveit.set_goal_position_tolerance(0.05)
left_arm_moveit.set_goal_orientation_tolerance(0.1)
left_arm_moveit.set_planning_time(1.0)
left_arm_moveit.set_goal_position_tolerance(0.005)
left_arm_moveit.set_goal_orientation_tolerance(0.01)
left_arm_moveit.set_planning_time(5.0)
#left_arm_moveit.compute_cartesian_path()

#left_arm_moveit.set_num_planning_attempts(10)
left_arm_moveit.allow_replanning(True)
left_arm_moveit.set_max_velocity_scaling_factor(0.4)
left_arm_moveit.set_max_acceleration_scaling_factor(0.2)
left_arm_moveit.set_max_velocity_scaling_factor(0.1)
left_arm_moveit.set_max_acceleration_scaling_factor(0.1)

right_arm_moveit.set_goal_position_tolerance(0.005)
right_arm_moveit.set_goal_orientation_tolerance(0.01)
Expand Down Expand Up @@ -185,7 +185,7 @@ def main():
left_go2pose_input = left_go2poseRequest()
left_go2pose_input.goal_position = Vector3(x_waypoints[i],y_waypoints[i],z_waypoints[i])
#Step_input.Gripper_state = gripper_state[i]
#left_go2pose_input.goal_orientation = left_current_pose.orientation #Quaternion(-0.3801916530737042,0.9235212614290408, 0.020782280350508237, 0.0461614930979309)
left_go2pose_input.goal_orientation = left_current_pose.orientation#Quaternion(-0.3801916530737042,0.9235212614290408, 0.020782280350508237, 0.0461614930979309)

rospy.logerr(left_go2pose_input)
left_go2pose_service(left_go2pose_input)
Expand All @@ -199,12 +199,11 @@ def main():
waypoints.append(pose)
rospy.logerr(waypoints)
(plan, fraction) = left_arm_moveit.compute_cartesian_path(waypoints, 0.01, 0, avoid_collisions=True)
'''
left_arm_moveit.execute(plan, wait=True)
#left_arm_moveit.go()
left_arm_moveit.stop()
left_arm_moveit.clear_pose_targets()
'''
return {'response': "Done"}

#Define start_callback service
Expand Down

0 comments on commit c520a08

Please sign in to comment.