Skip to content

Commit

Permalink
CI対応
Browse files Browse the repository at this point in the history
  • Loading branch information
mizonon committed Nov 1, 2024
1 parent 8ab3822 commit c122fb8
Show file tree
Hide file tree
Showing 9 changed files with 41 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -104,5 +104,5 @@ def main(args=None):
rclpy.shutdown()


if __name__ == "__main__":
if __name__ == '__main__':
main()
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
from image_geometry import PinholeCameraModel
import rclpy
from rclpy.node import Node
import tf2_ros
from sensor_msgs.msg import CameraInfo, Image
import tf2_ros


class ImageSubscriber(Node):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,5 +92,5 @@ def main(args=None):
rclpy.shutdown()


if __name__ == "__main__":
if __name__ == '__main__':
main()
4 changes: 2 additions & 2 deletions crane_plus_examples_py/crane_plus_examples_py/joint_values.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,12 @@
from crane_plus_examples_py.utils import plan_and_execute

# moveit python library
from moveit.core.kinematic_constraints import construct_joint_constraint
from moveit.core.robot_state import RobotState
from moveit.planning import (
MoveItPy,
PlanRequestParameters,
)
from moveit.core.kinematic_constraints import construct_joint_constraint
import rclpy
from rclpy.logging import get_logger

Expand Down Expand Up @@ -91,5 +91,5 @@ def main(args=None):
rclpy.shutdown()


if __name__ == "__main__":
if __name__ == '__main__':
main()
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from crane_plus_examples_py.utils import plan_and_execute, euler_to_quaternion
from crane_plus_examples_py.utils import euler_to_quaternion, plan_and_execute
from geometry_msgs.msg import PoseStamped

import math

# moveit python library
Expand Down Expand Up @@ -66,7 +67,7 @@ def main(args=None):
gripper_plan_request_params.max_acceleration_scaling_factor = 1.0

# Set 0.0 ~ 1.0
gripper_plan_request_params.max_velocity_scaling_factor = 1.0
gripper_plan_request_params.max_velocity_scaling_factor = 1.0

# gripperの開閉角度
GRIPPER_DEFAULT = 0.0
Expand Down Expand Up @@ -275,5 +276,5 @@ def main(args=None):
rclpy.shutdown()


if __name__ == "__main__":
if __name__ == '__main__':
main()
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,11 @@

import datetime

from crane_plus_examples_py.utils import plan_and_execute, euler_to_quaternion

from geometry_msgs.msg import Pose
from crane_plus_examples_py.utils import euler_to_quaternion, plan_and_execute

import math

import numpy as np
from geometry_msgs.msg import Pose

# moveit python library
from moveit.core.robot_state import RobotState
Expand All @@ -29,12 +27,15 @@
MoveItPy,
PlanRequestParameters,
)

import numpy as np

import rclpy
from rclpy.logging import get_logger
from rclpy.node import Node
from rclpy.time import Time
import tf2_ros
from tf2_ros import TransformStamped, TransformListener
from tf2_ros import TransformListener, TransformStamped
from tf2_ros.buffer import Buffer


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ def main(args=None):
crane_plus,
'ompl_rrtc',
)

# 速度&加速度のスケーリングファクタを設定
plan_request_params.max_acceleration_scaling_factor = 1.0 # Set 0.0 ~ 1.0
plan_request_params.max_velocity_scaling_factor = 1.0 # Set 0.0 ~ 1.0
Expand Down Expand Up @@ -82,5 +82,5 @@ def main(args=None):
rclpy.shutdown()


if __name__ == "__main__":
if __name__ == '__main__':
main()
6 changes: 3 additions & 3 deletions crane_plus_examples_py/crane_plus_examples_py/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,11 @@
# limitations under the License.

import numpy as np

from rclpy.logging import get_logger

import time

import quaternion


Expand All @@ -35,15 +38,12 @@ def plan_and_execute(
plan_result = planning_component.plan(
multi_plan_parameters=multi_plan_parameters
)
logger.info('plan_result >>>>> multi', once=True)
elif single_plan_parameters is not None:
plan_result = planning_component.plan(
single_plan_parameters=single_plan_parameters
)
logger.info('plan_result >>>>> single', once=True)
else:
plan_result = planning_component.plan()
logger.info('plan_result >>>>> none', once=True)

# execute the plan
result = None
Expand Down
43 changes: 21 additions & 22 deletions crane_plus_examples_py/launch/camera_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
import os

from ament_index_python.packages import get_package_share_directory
from crane_plus_description.robot_description_loader import RobotDescriptionLoader
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
Expand All @@ -25,41 +24,41 @@

def generate_launch_description():
moveit_config = (
MoveItConfigsBuilder("crane_plus")
MoveItConfigsBuilder('crane_plus')
.planning_scene_monitor(
publish_robot_description=True,
publish_robot_description_semantic=True,
)
.robot_description(
file_path=os.path.join(
get_package_share_directory("crane_plus_description"),
"urdf",
"crane_plus.urdf.xacro",
get_package_share_directory('crane_plus_description'),
'urdf',
'crane_plus.urdf.xacro',
),
mappings={},
)
.robot_description_semantic(
file_path="config/crane_plus.srdf",
mappings={"model": "crane_plus"},
file_path='config/crane_plus.srdf',
mappings={'model': 'crane_plus'},
)
.joint_limits(file_path="config/joint_limits.yaml")
.joint_limits(file_path='config/joint_limits.yaml')
.trajectory_execution(
file_path="config/controllers.yaml", moveit_manage_controllers=True
file_path='config/controllers.yaml', moveit_manage_controllers=True
)
.planning_pipelines(pipelines=["ompl"])
.robot_description_kinematics(file_path="config/kinematics.yaml")
.planning_pipelines(pipelines=['ompl'])
.robot_description_kinematics(file_path='config/kinematics.yaml')
.moveit_cpp(
file_path=get_package_share_directory("crane_plus_examples_py")
+ "/config/crane_plus_moveit_py_examples.yaml"
file_path=get_package_share_directory('crane_plus_examples_py')
+ '/config/crane_plus_moveit_py_examples.yaml'
)
.to_moveit_configs()
)

moveit_config.robot_description = {
"robot_description": LaunchConfiguration("loaded_description")
'robot_description': LaunchConfiguration('loaded_description')
}

moveit_config.move_group_capabilities = {"capabilities": ""}
moveit_config.move_group_capabilities = {'capabilities': ''}

declare_example_name = DeclareLaunchArgument(
'example', default_value='color_detection',
Expand All @@ -69,21 +68,21 @@ def generate_launch_description():

picking_node = Node(
name='pick_and_place_tf',
package="crane_plus_examples_py",
package='crane_plus_examples_py',
executable='pick_and_place_tf',
output="screen",
output='screen',
parameters=[
moveit_config.robot_description,
moveit_config.robot_description_semantic,
moveit_config.robot_description_kinematics,
],
)

detection_node = Node(
name=[LaunchConfiguration("example"), "_node"],
package="crane_plus_examples_py",
executable=LaunchConfiguration("example"),
output="screen"
name=[LaunchConfiguration('example'), '_node'],
package='crane_plus_examples_py',
executable=LaunchConfiguration('example'),
output='screen'
)

ld = LaunchDescription()
Expand Down

0 comments on commit c122fb8

Please sign in to comment.