Fixed configs and added real ratios for J1 and J2

This commit is contained in:
Thomas Muller 2021-09-23 14:28:45 +00:00
parent 21440062d4
commit 724839cf19
4 changed files with 174 additions and 164 deletions

View file

@ -1,7 +1,9 @@
controller_names: moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
moveit_simple_controller_manager:
controller_names:
- joint_trajectory_controller - joint_trajectory_controller
joint_trajectory_controller: joint_trajectory_controller:
action_ns: follow_joint_trajectory action_ns: follow_joint_trajectory
type: FollowJointTrajectory type: FollowJointTrajectory
default: true default: true

View file

@ -1,4 +1,10 @@
planner_configs: move_group:
planning_plugin: ompl_interface/OMPLPlanner
request_adapters:
default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
planner_configs:
SBLkConfigDefault: SBLkConfigDefault:
type: geometric::SBL type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@ -121,7 +127,7 @@ planner_configs:
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000 max_failures: 5000 # maximum consecutive failure limit. default: 5000
ar3_arm: ar3_arm:
default_planner_config: RRTConnectkConfigDefault default_planner_config: RRTConnectkConfigDefault
planner_configs: planner_configs:
- SBLkConfigDefault - SBLkConfigDefault

View file

@ -72,8 +72,10 @@ def generate_launch_description():
robot_description, robot_description,
robot_description_semantic, robot_description_semantic,
robot_description_kinematics, robot_description_kinematics,
{'move_group': join(config_root, 'ompl_planning.yaml')}, get_yaml(join(config_root, 'ompl_planning.yaml')),
{'moveit_simple_controller_manager': join(config_root, "ar3_controllers.yaml")}, get_yaml(join(config_root, 'trajectory.yaml')),
get_yaml(join(config_root, 'planning_scene.yaml')),
get_yaml(join(config_root, "ar3_controllers.yaml")),
], ],
), ),

View file

@ -46,11 +46,11 @@ class CobotMove(Node):
print(self._serial.readline()) print(self._serial.readline())
def _move_j1_cb(self, msg): def _move_j1_cb(self, msg):
self._cur[0] = int(msg.data / pi / 2. * 2000) self._cur[0] = int(msg.data / pi / 2. * 8000)
self._move_servo() self._move_servo()
def _move_j2_cb(self, msg): def _move_j2_cb(self, msg):
self._cur[1] = int(msg.data / pi / 2. * 3840.64) self._cur[1] = int(msg.data / pi / 2. * 10000)
self._move_servo() self._move_servo()
def _move_j3_cb(self, msg): def _move_j3_cb(self, msg):