Fixed configs and added real ratios for J1 and J2
This commit is contained in:
parent
21440062d4
commit
724839cf19
4 changed files with 174 additions and 164 deletions
|
@ -1,3 +1,5 @@
|
||||||
|
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
|
||||||
|
moveit_simple_controller_manager:
|
||||||
controller_names:
|
controller_names:
|
||||||
- joint_trajectory_controller
|
- joint_trajectory_controller
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,9 @@
|
||||||
|
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:
|
planner_configs:
|
||||||
SBLkConfigDefault:
|
SBLkConfigDefault:
|
||||||
type: geometric::SBL
|
type: geometric::SBL
|
||||||
|
|
|
@ -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")),
|
||||||
],
|
],
|
||||||
),
|
),
|
||||||
|
|
||||||
|
|
|
@ -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):
|
||||||
|
|
Loading…
Reference in a new issue