Change acceleration limit and cartesian limit

This commit is contained in:
2023-03-10 13:29:29 +02:00
parent fe1a40cbc2
commit e64aa4fbae
3 changed files with 21 additions and 3 deletions

View File

@@ -302,7 +302,7 @@ def launch_setup(context, *args, **kwargs):
# FIX acceleration limits # FIX acceleration limits
for i in range(1,7): for i in range(1,7):
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 0.5 joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin' kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
#kinematics_yaml['kinematics_solver'] = 'lma_kinematics_plugin/LMAKinematicsPlugin' #kinematics_yaml['kinematics_solver'] = 'lma_kinematics_plugin/LMAKinematicsPlugin'
@@ -336,6 +336,12 @@ def launch_setup(context, *args, **kwargs):
prefix=prefix.perform(context)) prefix=prefix.perform(context))
robot_description_parameters['cartesian_limits'] = {}
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
# Planning pipeline # Planning pipeline
# https://github.com/AndrejOrsula/panda_moveit2_config/blob/master/launch/move_group_fake_control.launch.py # https://github.com/AndrejOrsula/panda_moveit2_config/blob/master/launch/move_group_fake_control.launch.py

View File

@@ -154,6 +154,12 @@ def launch_setup(context, *args, **kwargs):
ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, 'ompl_planning.yaml') ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, 'ompl_planning.yaml')
kinematics_yaml = robot_description_parameters['robot_description_kinematics'] kinematics_yaml = robot_description_parameters['robot_description_kinematics']
robot_description_parameters['cartesian_limits'] = {}
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
#kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin' #kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
#kinematics_yaml['kinematics_solver_search_resolution'] = 0.005 #kinematics_yaml['kinematics_solver_search_resolution'] = 0.005
#kinematics_yaml['kinematics_solver_timeout'] = 0.005 #kinematics_yaml['kinematics_solver_timeout'] = 0.005
@@ -182,7 +188,7 @@ def launch_setup(context, *args, **kwargs):
# FIX acceleration limits # FIX acceleration limits
for i in range(1,7): for i in range(1,7):
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 0.5 joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
add_prefix_to_moveit_params = getattr(mod, 'add_prefix_to_moveit_params') add_prefix_to_moveit_params = getattr(mod, 'add_prefix_to_moveit_params')
add_prefix_to_moveit_params( add_prefix_to_moveit_params(

View File

@@ -158,7 +158,7 @@ def launch_setup(context, *args, **kwargs):
# FIX acceleration limits # FIX acceleration limits
for i in range(1,7): for i in range(1,7):
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 0.5 joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
if add_gripper.perform(context) in ('True', 'true'): if add_gripper.perform(context) in ('True', 'true'):
gripper_controllers_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), '{}.yaml'.format(controllers_name.perform(context))) gripper_controllers_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), '{}.yaml'.format(controllers_name.perform(context)))
@@ -182,6 +182,12 @@ def launch_setup(context, *args, **kwargs):
kinematics_yaml=kinematics_yaml, joint_limits_yaml=joint_limits_yaml, kinematics_yaml=kinematics_yaml, joint_limits_yaml=joint_limits_yaml,
prefix=prefix.perform(context)) prefix=prefix.perform(context))
robot_description_parameters['cartesian_limits'] = {}
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
# Planning Configuration # Planning Configuration
ompl_planning_pipeline_config = { ompl_planning_pipeline_config = {
'move_group': { 'move_group': {