├── .clang-format ├── .clang-tidy ├── .gitignore ├── README.md ├── thorp_apps ├── CMakeLists.txt ├── README.md ├── launch │ ├── cat_hunter.launch │ ├── explore_house.launch │ ├── includes │ │ └── apps_common.launch.xml │ ├── object_gatherer.launch │ ├── object_manip.launch │ ├── patrol_2_points.launch │ ├── pickup_objects.launch │ └── stack_all_cubes.launch ├── package.xml ├── param │ └── apps_config.yaml └── resources │ └── movie_scripts │ ├── cat_hunter.bt.yaml │ ├── cat_hunter.smach.yaml │ ├── explore_house.bt.yaml │ └── object_gatherer.yaml ├── thorp_boards ├── CMakeLists.txt ├── README.md ├── graveyard │ ├── CM9_BC.cpp__KK │ ├── CM9_BC.h__KK │ ├── arduino.cpp.Bosch │ ├── arduino.cpp_LASER │ ├── arduino.hpp.Basch │ ├── arduino.hpp_LASER │ ├── arduino.ino.readAnalog │ ├── opencm.h_PRE_EXPERIMENTS │ ├── opencm.ino_OLD_EXPERIMENTS │ └── opencm.ino_PRE_EXPERIMENTS ├── include │ └── thorp_boards │ │ └── arduino.hpp ├── launch │ ├── arduino.launch │ └── opencm.launch ├── package.xml ├── param │ ├── arduino.yaml │ └── opencm.yaml ├── resources │ ├── 58-arduino.rules │ ├── 59-opencm.rules │ ├── 60-usb2ax.rules │ ├── sharp_calib.m │ └── sonar_poses.m └── src │ ├── arduino │ ├── arduino.cpp │ ├── arduino_node.cpp │ └── firmware │ │ └── arduino │ │ ├── Makefile │ │ ├── arduino.ino │ │ └── setup.sh │ └── opencm │ ├── firmware │ ├── README.md │ └── opencm │ │ ├── CM9_BC.cpp.fixed │ │ ├── CM9_BC.h.fixed │ │ ├── opencm.h │ │ └── opencm.ino │ ├── ir_ranger.py │ └── sensors.py ├── thorp_bringup ├── CMakeLists.txt ├── README.md ├── docker │ ├── .dockerignore │ ├── Dockerfile │ ├── patch_ignition.yaml │ └── thorp.rosinstall ├── graveyard │ ├── block_gatherer.launch.SIM_APP │ ├── block_manip.launch │ ├── block_manip.launch.SIM_APP │ ├── block_manip_external.launch │ ├── exec_smach.launch.BAK │ ├── exec_smach.launch.NO_GROUPS │ ├── keyboard_ctrl.py │ ├── object_manip.launch.BAK │ ├── show_tk_fonts.py │ ├── thorp_playground.launch.BAK │ └── virt_sensor.launch.xml ├── launch │ ├── calibrate.launch │ ├── includes │ │ ├── autodock.launch.xml │ │ ├── kinect.launch.xml │ │ ├── master_ctrl.launch.xml │ │ ├── model.launch.xml │ │ ├── safety_ctrl.launch.xml │ │ ├── senz3d.launch.xml │ │ ├── state_publisher.launch.xml │ │ └── xtion.launch.xml │ ├── moveit.launch │ ├── navigation.launch │ ├── object_rec.launch │ ├── sonar_nav.launch │ ├── test_arm.launch │ ├── thorp_robot.launch │ ├── thorp_viz.launch │ └── view_model.launch ├── package.xml ├── param │ ├── kinect │ │ └── depthimage_to_laserscan.yaml │ ├── named_configs │ │ ├── precise_controlling.yaml │ │ └── waypoints_following.yaml │ ├── senz3d │ │ ├── calibration.yaml │ │ ├── manipulation.yaml │ │ └── obj_recognition.yaml │ ├── vel_multiplexer.yaml │ └── xtion │ │ └── pointcloud_to_laserscan.yaml ├── rviz │ ├── exploration.rviz │ ├── gathering.rviz │ ├── hunting.movie.rviz │ ├── hunting.rviz │ ├── icons │ │ ├── clear.png │ │ ├── exit.png │ │ ├── fold.png │ │ ├── reset.png │ │ ├── start.png │ │ └── stop.png │ ├── manipulation.rviz │ ├── navigation.rviz │ ├── perception.rviz │ ├── user_commands.yaml │ ├── view_all.rviz │ └── view_model.rviz └── scripts │ ├── aliencontrol.py │ ├── fake_joint_pub.py │ ├── fake_servos_srv.py │ ├── gripper_cmd.py │ └── user_commands.py ├── thorp_bt_cpp ├── CMakeLists.txt ├── bt │ ├── cat_hunter.xml │ ├── exploration.xml │ ├── explore_house.xml │ ├── manipulation.xml │ ├── navigation.xml │ ├── node_models.xml │ ├── object_gatherer.xml │ ├── object_manip.xml │ ├── patrol_2_points.xml │ └── pickup_objects.xml ├── groot │ └── thorp.btproj ├── include │ └── thorp_bt_cpp │ │ ├── bt_ros_logger.hpp │ │ ├── bt_runner.hpp │ │ ├── node_register.hpp │ │ ├── ros_action_node.hpp │ │ ├── ros_service_node.hpp │ │ ├── ros_subscriber_node.hpp │ │ └── type_converters.hpp ├── launch │ └── bt_runner.launch ├── package.xml ├── scripts │ └── show_bt_node_on_rviz.py └── src │ ├── bt │ ├── actions │ │ ├── add_object_to_tray.cpp │ │ ├── cannon_control.cpp │ │ ├── clear_costmaps.cpp │ │ ├── clear_gripper.cpp │ │ ├── clear_list.cpp │ │ ├── clear_octomap.cpp │ │ ├── clear_planning_scene.cpp │ │ ├── clear_rail_markers.cpp │ │ ├── clear_table_access.cpp │ │ ├── detect_objects.cpp │ │ ├── detect_tables.cpp │ │ ├── drag_and_drop.cpp │ │ ├── exe_path.cpp │ │ ├── expand_pickup_location.cpp │ │ ├── follow_pose.cpp │ │ ├── get_closest_pose.cpp │ │ ├── get_from_list.cpp │ │ ├── get_list_front.cpp │ │ ├── get_path.cpp │ │ ├── get_poses_around_table.cpp │ │ ├── get_robot_pose.cpp │ │ ├── go_to_pose.cpp │ │ ├── list_slicing.cpp │ │ ├── look_at_pose.cpp │ │ ├── make_pickup_plan.cpp │ │ ├── monitor_objects.cpp │ │ ├── next_pose_on_tray.cpp │ │ ├── pickup_object.cpp │ │ ├── place_object.cpp │ │ ├── plan_room_exploration.cpp │ │ ├── plan_room_sequence.cpp │ │ ├── pop_from_list.cpp │ │ ├── pose_as_path.cpp │ │ ├── push_to_list.cpp │ │ ├── read_ros_param.cpp │ │ ├── read_user_commands.cpp │ │ ├── record_pickup_failure.cpp │ │ ├── recovery.cpp │ │ ├── restore_table_access.cpp │ │ ├── segment_rooms.cpp │ │ ├── select_next_target.cpp │ │ ├── set_arm_config.cpp │ │ ├── set_blackboard.cpp │ │ ├── smooth_path.cpp │ │ ├── switch_safety_controller.cpp │ │ ├── table_as_obstacle.cpp │ │ ├── track_progress.cpp │ │ ├── transform_pose.cpp │ │ └── use_named_config.cpp │ ├── conditions │ │ ├── are_same_pose.cpp │ │ ├── bumper_pressed.cpp │ │ ├── camera_fov_clear.cpp │ │ ├── cannon_has_ammo.cpp │ │ ├── gripper_busy.cpp │ │ ├── in_blackboard.cpp │ │ ├── is_bool_true.cpp │ │ ├── is_list_empty.cpp │ │ ├── object_attached.cpp │ │ ├── objects_detected.cpp │ │ ├── table_valid_size.cpp │ │ ├── table_visited.cpp │ │ ├── target_reachable.cpp │ │ └── tray_full.cpp │ ├── controls │ │ └── recover_and_retry.cpp │ └── decorators │ │ ├── for_each.cpp │ │ └── store_result.cpp │ ├── bt_ros_logger.cpp │ ├── bt_runner.cpp │ └── bt_runner_node.cpp ├── thorp_cannon ├── CMakeLists.txt ├── README.md ├── launch │ └── cannon.launch ├── nodes │ └── cannon_ctrl.py ├── package.xml ├── scripts │ └── cannon_cmd.py └── src │ └── gazebo_cannon_plugin.cpp ├── thorp_costmap_layers ├── CMakeLists.txt ├── cfg │ └── SemanticLayer.cfg ├── include │ └── thorp_costmap_layers │ │ ├── base_interface.hpp │ │ ├── semantic_layer.hpp │ │ ├── spatial_hash.hpp │ │ ├── srv_iface_client.hpp │ │ ├── srv_interface.hpp │ │ └── visualization.hpp ├── msg │ └── Object.msg ├── package.xml ├── plugins │ └── semantic_layer.xml ├── scripts │ └── clear_semantic_layer.py ├── setup.py ├── src │ ├── base_interface.cpp │ ├── semantic_layer.cpp │ ├── spatial_hash.cpp │ ├── srv_iface_client.cpp │ ├── srv_interface.cpp │ ├── thorp_costmap_layers │ │ ├── __init__.py │ │ └── srv_iface_client.py │ └── visualization.cpp ├── srv │ ├── QueryObjects.srv │ └── UpdateObjects.srv └── test │ └── test_semantic_layer.py ├── thorp_description ├── CMakeLists.txt ├── README.md ├── config │ └── tray.yaml ├── meshes │ ├── arm_mount.stl │ ├── asus_xtion_pro_live.dae │ ├── asus_xtion_pro_live.png │ ├── charging_station │ │ ├── model.config │ │ └── model.sdf │ ├── orig_arm_mount.stl │ ├── senz3d_mount.stl │ ├── sonar_array.dae │ ├── sonar_array.stl │ ├── tray.stl │ ├── tray_w_holes.stl │ ├── xtion_mount.stl │ ├── xtion_mount_a45.stl │ └── xtion_mount_a45_low.stl ├── package.xml ├── scripts │ ├── arm_mount.scad │ ├── calc_inertia.m │ ├── tray.scad │ ├── tubes_poses.m │ └── xtion_mount.scad └── urdf │ ├── calib │ ├── cannon.urdf.xacro │ ├── kinect.urdf.xacro │ ├── senz3d.urdf.xacro │ ├── standalone_arm.urdf.xacro │ ├── thorp.urdf.xacro │ ├── thorp.urdf.xacro.senz3d │ ├── thorp_gazebo.urdf.xacro │ └── xtion.urdf.xacro ├── thorp_exploration ├── CMakeLists.txt ├── README.md ├── launch │ └── exploration.launch ├── package.xml └── param │ ├── room_exploration_kinect.yaml │ ├── room_exploration_xtion.yaml │ ├── room_segmentation.yaml │ └── room_sequence_planning.yaml ├── thorp_manipulation ├── CMakeLists.txt ├── README.md ├── graveyard │ ├── MOVE_GROUP_pickup_object_server.cpp │ ├── MOVE_GROUP_place_object_server.cpp │ ├── has_effort.hpp │ └── pickup_object_server.cpp.W_DEBUG_x_aligned ├── include │ └── thorp_manipulation │ │ ├── house_keeping_server.hpp │ │ ├── joint_state_watchdog.hpp │ │ ├── move_to_target_server.hpp │ │ ├── pickup_object_server.hpp │ │ ├── place_object_server.hpp │ │ ├── thorp_arm_controller.hpp │ │ └── tray_manager_server.hpp ├── launch │ ├── includes │ │ ├── arm.launch.xml │ │ └── controllers.launch.xml │ └── manipulation.launch ├── nodes │ ├── dynamixel_joint_state_publisher.py │ ├── dynamixel_relax_all_servos.py │ └── pickup_planner_server.py ├── package.xml ├── param │ ├── controllers.yaml │ ├── pick_and_place.yaml │ └── pick_and_place_gazebo.yaml ├── scripts │ ├── test_arm_ctrl_servers.py │ └── test_pickup_object.py ├── setup.py └── src │ ├── house_keeping_server.cpp │ ├── interactive_manip_server.cpp │ ├── joint_state_watchdog.cpp │ ├── manipulation_server.cpp │ ├── move_to_target_server.cpp │ ├── pickup_object_server.cpp │ ├── place_object_server.cpp │ ├── thorp_arm_controller.cpp │ └── tray_manager_server.cpp ├── thorp_mbf_plugins ├── CMakeLists.txt ├── include │ └── thorp_mbf_plugins │ │ └── slow_escape_recovery.h ├── package.xml ├── plugins │ └── slow_escape_recovery.xml └── src │ └── slow_escape_recovery.cpp ├── thorp_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── Thorp.srdf │ ├── Thorp_pincher.srdf │ ├── cartesian_limits.yaml │ ├── chomp_planning.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ └── sensors_3d.yaml ├── launch │ ├── Thorp_moveit_controller_manager.launch.xml │ ├── Thorp_moveit_sensor_manager.launch.xml │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── demo_gazebo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── gazebo.launch │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── pilz_industrial_motion_planner_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml └── package.xml ├── thorp_msgs ├── CMakeLists.txt ├── action │ ├── DetectObjects.action │ ├── DragAndDrop.action │ ├── FollowPose.action │ ├── MakePickupPlan.action │ ├── MoveToTarget.action │ ├── PickupObject.action │ ├── PlaceObject.action │ └── UserCommand.action ├── msg │ ├── BTNodeStatus.msg │ ├── KeyboardInput.msg │ ├── ObjectToPickup.msg │ ├── PickupLocation.msg │ ├── PickupPlan.msg │ └── ThorpError.msg ├── package.xml └── srv │ ├── CannonCommand.srv │ ├── ClearPlanningScene.srv │ ├── ConnectWaypoints.srv │ ├── TrayAddObject.srv │ ├── TrayCapacity.srv │ └── TrayNextPose.srv ├── thorp_navigation ├── CMakeLists.txt ├── README.md ├── cfg │ └── Follower.cfg ├── graveyard │ ├── custom_move_base.yaml │ ├── global_dynamic_costmap.yaml │ ├── include │ │ └── thorp_navigation │ │ │ └── visual_servoing.hpp │ ├── launch │ │ ├── move_base.launch.xml │ │ └── move_base_eband.launch.xml │ ├── navigation.launch.smooth_follow │ ├── nodelet │ │ ├── CMakeLists.txt │ │ ├── nodes │ │ │ └── pose_follower.cpp │ │ ├── package.xml │ │ ├── plugins │ │ │ └── nodelets.xml │ │ └── pose_follower.cpp │ ├── param │ │ ├── behavior_trees.yaml │ │ ├── local_planners.yaml │ │ ├── move_base │ │ │ ├── README.md │ │ │ ├── base_local_planner_params.yaml │ │ │ ├── costmap_common_params.yaml │ │ │ ├── eband_planner_params.yaml │ │ │ ├── global_cm_sonar_params.yaml │ │ │ ├── global_costmap_params.yaml │ │ │ ├── local_costmap_params.yaml │ │ │ └── move_base_params.yaml │ │ ├── move_base_flex___.yaml │ │ ├── recovery_behaviors.yaml │ │ ├── teb_local_planner_params.yaml │ │ ├── teb_local_planner_params3.yaml │ │ └── vel_smoother.yaml │ ├── pose_follower.cpp_act_on_pose_cb │ ├── pose_follower.cpp_w_enable_srv │ ├── setup.py │ └── waypoints_path.cpp_DEBUG ├── include │ └── thorp_navigation │ │ └── waypoints_path.hpp ├── launch │ ├── includes │ │ ├── amcl.launch.xml │ │ └── move_base_flex.launch.xml │ └── navigation.launch ├── maps │ ├── dorothy_cafe.pgm │ ├── dorothy_cafe.yaml │ ├── edu_room_cropped.pgm │ ├── edu_room_cropped.yaml │ ├── empty.png │ ├── empty.yaml │ ├── frieburg.png │ ├── frieburg.yaml │ ├── fun_house.png │ ├── fun_house.yaml │ ├── graz_home.pgm │ ├── graz_home.yaml │ ├── hospital_section.png │ ├── hospital_section.yaml │ ├── maze.png │ ├── maze.yaml │ ├── mines.png │ ├── mines.yaml │ ├── playground.png │ ├── playground.yaml │ ├── robocup.png │ ├── robocup.yaml │ ├── robopark2.bmp │ ├── robopark_plan.yaml │ ├── simple_rooms.png │ ├── simple_rooms.yaml │ ├── small_house.png │ ├── small_house.yaml │ ├── sparse_obstacles.png │ └── sparse_obstacles.yaml ├── nodes │ ├── mbf_simple_goal_relay.py │ └── show_velocity.py ├── package.xml ├── param │ ├── move_base_flex │ │ ├── common_costmap.yaml │ │ ├── dwa_local_planner.yaml │ │ ├── follower_planner.yaml │ │ ├── global_costmap.yaml │ │ ├── global_planners.yaml │ │ ├── local_costmap.yaml │ │ ├── move_base_flex.yaml │ │ ├── recovery_behaviors.yaml │ │ ├── teb_local_planner.yaml │ │ └── tro_local_planner.yaml │ ├── pose_follower.yaml │ ├── vel_smoother.yaml │ ├── vel_smoother_gazebo.yaml │ └── waypoints_path.yaml ├── scripts │ └── test │ │ ├── call_exe_path_and_cancel.py │ │ ├── call_get_path_and_cancel.py │ │ ├── call_get_path_twice.py │ │ ├── call_move_base_and_cancel.py │ │ ├── call_move_base_and_exe_path.py │ │ ├── call_path_smoother.py │ │ ├── call_path_smoother_n_teb.py │ │ ├── call_pose_follower.py │ │ ├── call_teb_single_pose_path.py │ │ └── spam_exe_path.py └── src │ ├── pose_follower.cpp │ ├── pose_servoing.cpp │ ├── visual_servoing.cpp │ └── waypoints_path.cpp ├── thorp_perception ├── CMakeLists.txt ├── config │ ├── cob │ │ ├── object_detection.yaml │ │ └── object_projection.yaml │ ├── ork │ │ ├── external.tabletop.detection.ros.ork │ │ ├── linemod.detection.ros.ork │ │ ├── tabletop.detection.ros.ork │ │ └── tod.detection.ros.ork │ └── rail │ │ ├── segmentation.yaml │ │ └── zones.yaml ├── graveyard │ ├── experimental.detection.object.ros.ork │ ├── launch │ │ ├── kinect_tabletop.launch │ │ ├── ork_capture.launch │ │ ├── ork_softkinetic.launch │ │ ├── ork_template.launch │ │ ├── ork_track.launch │ │ ├── perception.launch.xml.cob │ │ ├── perception.launch.xml.ork │ │ ├── perception.launch.xml.rail │ │ └── ubr1_grasp.launch │ ├── object_detection_color_HSV.hpp │ ├── object_detection_color_KMEANS.hpp │ ├── pick_and_place.py │ ├── projection.py │ ├── rail_object_detection_server.cpp_DIRTY │ └── senz3d.tabletop.detection.ros.ork ├── include │ └── thorp_perception │ │ ├── object_detection_bin.hpp │ │ ├── object_detection_color.hpp │ │ ├── object_detection_table.hpp │ │ └── spatial_hash.hpp ├── launch │ ├── includes │ │ ├── obj_rec.launch.xml │ │ └── template_matcher.launch.xml │ └── perception.launch ├── meshes │ ├── blender │ │ ├── coke.blend │ │ ├── coke.mtl │ │ ├── coke.obj │ │ ├── coke.stl │ │ ├── cube_2_5.stl │ │ ├── cube_2_5.stl.blend │ │ ├── cube_2_5_blue.mtl │ │ ├── cube_2_5_blue.obj │ │ ├── cube_2_5_blue.ply │ │ ├── cube_2_5_green.mtl │ │ ├── cube_2_5_green.obj │ │ ├── cube_2_5_green.ply │ │ ├── cube_2_5_red.mtl │ │ ├── cube_2_5_red.obj │ │ ├── cube_2_5_red.ply │ │ ├── cube_2_5_red_2.mtl │ │ ├── cube_2_5_red_2.obj │ │ ├── orbit.blend │ │ ├── orbit.stl │ │ ├── tower_5.mtl │ │ ├── tower_5.obj │ │ ├── tower_5.stl │ │ └── tower_5.stl.blend │ ├── circle.pcd │ ├── circle.ply │ ├── circle.stl │ ├── clover.pcd │ ├── clover.ply │ ├── clover.stl │ ├── cross.pcd │ ├── cross.ply │ ├── cross.stl │ ├── cube.pcd │ ├── cube.ply │ ├── cube.stl │ ├── diamond.pcd │ ├── diamond.ply │ ├── diamond.stl │ ├── lipstick.pcd │ ├── lipstick.ply │ ├── lipstick.stl │ ├── pentagon.pcd │ ├── pentagon.ply │ ├── pentagon.stl │ ├── rectangle.pcd │ ├── rectangle.ply │ ├── rectangle.stl │ ├── square.pcd │ ├── square.ply │ ├── square.stl │ ├── star.pcd │ ├── star.ply │ ├── star.stl │ ├── tower.pcd │ ├── tower.ply │ ├── tower.stl │ ├── triangle.pcd │ ├── triangle.ply │ └── triangle.stl ├── nodes │ ├── object_tracking.py │ └── xtion_fov_analyzer.py ├── package.xml ├── scripts │ ├── generate_meshes.py │ ├── generate_meshes.scad │ ├── get_object_info_client.py │ ├── parametric_star.scad │ └── populate_ork_database.py └── src │ ├── ork_object_detection_server.cpp │ └── rail_object_detection_server.cpp ├── thorp_rviz_plugins ├── CMakeLists.txt ├── icons │ └── classes │ │ ├── CancelNavigationTool.png │ │ └── ClearCostmapTool.png ├── include │ └── thorp_rviz_plugins │ │ ├── button_tool.hpp │ │ ├── cancel_navigation_tool.hpp │ │ └── clear_costmap_tool.hpp ├── package.xml ├── plugins.xml └── src │ ├── button_tool.cpp │ ├── cancel_navigation_tool.cpp │ └── clear_costmap_tool.cpp ├── thorp_simulation ├── CMakeLists.txt ├── graveyard │ ├── arm_control.yaml │ ├── arm_control.yaml__BOOM │ ├── cat_house.world │ ├── cat_house_split.world │ ├── fun_house_straight.png │ ├── fun_house_w_3_tables.png │ ├── fun_house_w_outside.png │ ├── gazebo_cannon_plugin.cpp.SPAWN_ROCKET │ ├── gazebo_ground_truth.py │ ├── tb3_house.world │ └── thorp_alica.launch ├── launch │ ├── includes │ │ ├── sim_common.launch.xml │ │ ├── stdr_relays.launch.xml │ │ └── thorp_gazebo.launch.xml │ ├── navigation.launch │ ├── thorp_gazebo.launch │ ├── thorp_stage.launch │ └── thorp_stdr.launch ├── nodes │ ├── cats_controller.py │ ├── model_markers.py │ └── movie_director.py ├── package.xml ├── param │ └── controllers.yaml ├── robots │ ├── sensors │ │ ├── EZ2_sonar.yaml │ │ └── GP2Y0A21_ir.yaml │ ├── thorp.inc │ ├── thorp.yaml │ └── thorp_footprint.png ├── scripts │ ├── gazebo_link_state.py │ └── spawn_gazebo_models.py ├── src │ ├── gazebo_camera_control.cpp │ ├── gazebo_camera_control_plugin.cpp │ └── gazebo_ground_truth.cpp └── worlds │ ├── gazebo │ ├── empty.world │ ├── fun_house.world │ ├── models │ │ ├── camera_control │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── cat_black │ │ │ ├── meshes │ │ │ │ ├── Cat_bump.jpg │ │ │ │ ├── Cat_diffuse.jpg │ │ │ │ ├── Cat_v1_l3.mtl │ │ │ │ └── Cat_v1_l3.obj │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── cat_orange │ │ │ ├── meshes │ │ │ │ ├── Cat_bump.jpg │ │ │ │ ├── Cat_diffuse.jpg │ │ │ │ ├── Cat_v1_l3.mtl │ │ │ │ └── Cat_v1_l3.obj │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── circle │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── clover │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── coke │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── cross │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── cube │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── cube_20k │ │ │ ├── meshes │ │ │ │ └── cube_20k.stl │ │ │ ├── model-1_2.sdf │ │ │ ├── model-1_3.sdf │ │ │ ├── model-1_4.sdf │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── diamond │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── doll_table │ │ │ ├── Wood_Cherry_Original_.jpg │ │ │ ├── model.config │ │ │ ├── model.dae │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── dumpster │ │ │ ├── materials │ │ │ │ ├── scripts │ │ │ │ │ └── dumpster.material │ │ │ │ └── textures │ │ │ │ │ ├── Dumpster_Diffuse.png │ │ │ │ │ └── Dumpster_Spec.png │ │ │ ├── meshes │ │ │ │ └── dumpster.dae │ │ │ ├── model-1_3.sdf │ │ │ ├── model-1_4.sdf │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── first_2015_trash_can │ │ │ ├── meshes │ │ │ │ └── trash_can.dae │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── jersey_barrier │ │ │ ├── materials │ │ │ │ └── textures │ │ │ │ │ ├── jersey_barrier.png │ │ │ │ │ ├── jersey_barrier_diffuse.png │ │ │ │ │ └── jersey_barrier_spec.png │ │ │ ├── meshes │ │ │ │ └── jersey_barrier.dae │ │ │ ├── model-1_4.sdf │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── lack_table │ │ │ ├── model.config │ │ │ ├── model.scad │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── lack_table_x15 │ │ │ ├── model.config │ │ │ ├── model.scad │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── lipstick │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── mailbox │ │ │ ├── materials │ │ │ │ ├── scripts │ │ │ │ │ └── mailbox.material │ │ │ │ └── textures │ │ │ │ │ ├── Mailbox_Diffuse.png │ │ │ │ │ ├── Mailbox_Diffuse.tga.orig │ │ │ │ │ └── Mailbox_Spec.png │ │ │ ├── meshes │ │ │ │ └── mailbox.dae │ │ │ ├── model-1_3.sdf │ │ │ ├── model-1_4.sdf │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── pentagon │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── rectangle │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── rocket │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── square │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── star │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── templates │ │ │ ├── model.config │ │ │ └── model.sdf │ │ ├── tower │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── triangle │ │ │ ├── model.config │ │ │ ├── model.sdf │ │ │ └── model.stl │ │ ├── turtlebot3_house │ │ │ ├── model.config │ │ │ └── model.sdf │ │ └── wood_cube_2_5cm │ │ │ ├── model.config │ │ │ └── model.sdf │ ├── playground.world │ └── small_house.world │ └── stage │ ├── blocks.inc │ ├── empty.world │ ├── fun_house.world │ ├── maze.world │ ├── robopark_plan.world │ └── small_house.world ├── thorp_smach ├── CMakeLists.txt ├── graveyard │ ├── CATKIN_IGNORE │ ├── block_gatherer.py │ ├── block_manip.py │ ├── block_transport.py │ ├── calibration_tools │ │ ├── __init__.py │ │ ├── actuator.py │ │ └── msg_imports.py │ ├── config.py │ ├── launch │ │ ├── find_object.launch │ │ ├── korus_move_arm_planner_ik.launch │ │ ├── move_arm_ik.launch │ │ ├── move_arm_planner.launch │ │ ├── move_arm_planner_ik.launch │ │ ├── move_things_around.launch │ │ ├── patrol.launch │ │ ├── pick_object.launch │ │ ├── pick_object_manual.launch │ │ └── place_object.launch │ ├── manipulation.py_w_viz_obj │ ├── monitor_tables_w_cb.py │ ├── object_manip.py_CONC │ ├── object_manip.py_LOOP │ ├── object_manip.py_NEW │ ├── object_manip.py_NOWRAP │ ├── object_manip_tbarm.py │ ├── old_tray_states.py │ ├── perception.py.w_block_detection │ ├── pick_and_place_tools │ │ ├── __init__.py │ │ ├── ik.py │ │ ├── misc_tools.py │ │ ├── move_arm.py │ │ ├── msg_imports.py │ │ ├── object_recognition.py │ │ └── trajectory_control.py │ ├── scripts │ │ ├── calibration │ │ │ ├── arm_calibration.py │ │ │ ├── head_calibration.py │ │ │ └── upper_body_calibration.py │ │ ├── manipulation │ │ │ ├── move_arm_ik_as.py │ │ │ ├── move_arm_ik_client.py │ │ │ ├── move_arm_planner_as.py │ │ │ ├── move_arm_planner_client.py │ │ │ ├── move_arm_planner_ik_as.py │ │ │ ├── move_gripper_as.py │ │ │ ├── move_gripper_client.py │ │ │ ├── pick_object_as.py │ │ │ ├── pick_object_client.py │ │ │ ├── pick_object_manual_as.py │ │ │ ├── place_object_as.py │ │ │ └── place_object_client.py │ │ ├── mobile_manipulation │ │ │ └── move_things_around.py │ │ ├── object_recognition │ │ │ ├── find_object_as.py │ │ │ └── find_object_client.py │ │ └── test │ │ │ └── add_collision_object.py │ ├── segment_rooms_w_img.py │ ├── state_machines │ │ ├── __init__.py │ │ ├── arm_calibration_sm.py │ │ ├── find_object_sm.py │ │ ├── find_table_sm.py │ │ ├── head_calibration_sm.py │ │ ├── move_arm_ik_sm.py │ │ ├── move_arm_sm.py │ │ ├── pick_object_manual_sm.py │ │ ├── pick_object_sm.py │ │ ├── place_object_manual_sm.py │ │ ├── place_object_sm.py │ │ ├── prepare_ik_seeds_sm.py │ │ ├── state_machines_imports.py │ │ └── take_collision_map_snapshot_sm.py │ └── transformer.py ├── package.xml ├── scripts │ ├── run_look_to_pose_state.py │ └── show_state_on_rviz.py ├── setup.py └── src │ └── thorp_smach │ ├── __init__.py │ ├── cat_hunter.py │ ├── containers │ ├── __init__.py │ └── do_on_exit.py │ ├── explore_house.py │ ├── object_gatherer.py │ ├── object_manip.py │ ├── patrol_2_points.py │ ├── pickup_objects.py │ ├── stack_all_cubes.py │ ├── states │ ├── __init__.py │ ├── cannon_ctrl.py │ ├── common.py │ ├── costmaps.py │ ├── exploration.py │ ├── gathering.py │ ├── geometry.py │ ├── manipulation.py │ ├── navigation.py │ ├── perception.py │ ├── pickup_objs.py │ ├── semantics.py │ └── userdata.py │ └── utils.py └── thorp_toolkit ├── CMakeLists.txt ├── graveyard ├── UpdateCollisionObjs.srv ├── geometry_2d.cpp ├── geometry_2d.hpp ├── semantic_layer.py └── test_semantic_layer.py ├── include └── thorp_toolkit │ ├── alternative_config.hpp │ ├── common.hpp │ ├── geometry.hpp │ ├── kobuki_base.hpp │ ├── math.hpp │ ├── parameters.hpp │ ├── planning_scene.hpp │ ├── progress_tracker.hpp │ ├── reconfigure.hpp │ ├── simulation.hpp │ ├── spatial_hash.hpp │ ├── tf2.hpp │ └── visualization.hpp ├── nodes └── save_pose_node.cpp ├── package.xml ├── python └── thorp_toolkit │ ├── __init__.py │ ├── common.py │ ├── decorators.py │ ├── geometry.py │ ├── planning_scene.py │ ├── point_tracker.py │ ├── progress_tracker.py │ ├── reconfigure.py │ ├── semantic_map.py │ ├── singleton.py │ ├── spatial_hash.py │ ├── tachometer.py │ ├── transform.py │ └── visualization.py ├── setup.py ├── src ├── alternative_config.cpp ├── common.cpp ├── geometry.cpp ├── kobuki_base.cpp ├── planning_scene.cpp ├── progress_tracker.cpp ├── reconfigure.cpp ├── simulation.cpp ├── tf2.cpp └── visualization.cpp └── test ├── test_progress_tracker.py ├── test_reconfigure.py └── test_semantic_map.py /.clang-format: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/.clang-format -------------------------------------------------------------------------------- /.clang-tidy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/.clang-tidy -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/.gitignore -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/README.md -------------------------------------------------------------------------------- /thorp_apps/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_apps/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/README.md -------------------------------------------------------------------------------- /thorp_apps/launch/cat_hunter.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/cat_hunter.launch -------------------------------------------------------------------------------- /thorp_apps/launch/explore_house.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/explore_house.launch -------------------------------------------------------------------------------- /thorp_apps/launch/includes/apps_common.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/includes/apps_common.launch.xml -------------------------------------------------------------------------------- /thorp_apps/launch/object_gatherer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/object_gatherer.launch -------------------------------------------------------------------------------- /thorp_apps/launch/object_manip.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/object_manip.launch -------------------------------------------------------------------------------- /thorp_apps/launch/patrol_2_points.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/patrol_2_points.launch -------------------------------------------------------------------------------- /thorp_apps/launch/pickup_objects.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/pickup_objects.launch -------------------------------------------------------------------------------- /thorp_apps/launch/stack_all_cubes.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/launch/stack_all_cubes.launch -------------------------------------------------------------------------------- /thorp_apps/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/package.xml -------------------------------------------------------------------------------- /thorp_apps/param/apps_config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/param/apps_config.yaml -------------------------------------------------------------------------------- /thorp_apps/resources/movie_scripts/cat_hunter.bt.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/resources/movie_scripts/cat_hunter.bt.yaml -------------------------------------------------------------------------------- /thorp_apps/resources/movie_scripts/cat_hunter.smach.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/resources/movie_scripts/cat_hunter.smach.yaml -------------------------------------------------------------------------------- /thorp_apps/resources/movie_scripts/explore_house.bt.yaml: -------------------------------------------------------------------------------- 1 | cat_hunter.bt.yaml -------------------------------------------------------------------------------- /thorp_apps/resources/movie_scripts/object_gatherer.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_apps/resources/movie_scripts/object_gatherer.yaml -------------------------------------------------------------------------------- /thorp_boards/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_boards/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/README.md -------------------------------------------------------------------------------- /thorp_boards/graveyard/CM9_BC.cpp__KK: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/CM9_BC.cpp__KK -------------------------------------------------------------------------------- /thorp_boards/graveyard/CM9_BC.h__KK: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/CM9_BC.h__KK -------------------------------------------------------------------------------- /thorp_boards/graveyard/arduino.cpp.Bosch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/arduino.cpp.Bosch -------------------------------------------------------------------------------- /thorp_boards/graveyard/arduino.cpp_LASER: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/arduino.cpp_LASER -------------------------------------------------------------------------------- /thorp_boards/graveyard/arduino.hpp.Basch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/arduino.hpp.Basch -------------------------------------------------------------------------------- /thorp_boards/graveyard/arduino.hpp_LASER: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/arduino.hpp_LASER -------------------------------------------------------------------------------- /thorp_boards/graveyard/arduino.ino.readAnalog: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/arduino.ino.readAnalog -------------------------------------------------------------------------------- /thorp_boards/graveyard/opencm.h_PRE_EXPERIMENTS: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/opencm.h_PRE_EXPERIMENTS -------------------------------------------------------------------------------- /thorp_boards/graveyard/opencm.ino_OLD_EXPERIMENTS: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/opencm.ino_OLD_EXPERIMENTS -------------------------------------------------------------------------------- /thorp_boards/graveyard/opencm.ino_PRE_EXPERIMENTS: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/graveyard/opencm.ino_PRE_EXPERIMENTS -------------------------------------------------------------------------------- /thorp_boards/include/thorp_boards/arduino.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/include/thorp_boards/arduino.hpp -------------------------------------------------------------------------------- /thorp_boards/launch/arduino.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/launch/arduino.launch -------------------------------------------------------------------------------- /thorp_boards/launch/opencm.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/launch/opencm.launch -------------------------------------------------------------------------------- /thorp_boards/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/package.xml -------------------------------------------------------------------------------- /thorp_boards/param/arduino.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/param/arduino.yaml -------------------------------------------------------------------------------- /thorp_boards/param/opencm.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/param/opencm.yaml -------------------------------------------------------------------------------- /thorp_boards/resources/58-arduino.rules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/resources/58-arduino.rules -------------------------------------------------------------------------------- /thorp_boards/resources/59-opencm.rules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/resources/59-opencm.rules -------------------------------------------------------------------------------- /thorp_boards/resources/60-usb2ax.rules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/resources/60-usb2ax.rules -------------------------------------------------------------------------------- /thorp_boards/resources/sharp_calib.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/resources/sharp_calib.m -------------------------------------------------------------------------------- /thorp_boards/resources/sonar_poses.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/resources/sonar_poses.m -------------------------------------------------------------------------------- /thorp_boards/src/arduino/arduino.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/arduino/arduino.cpp -------------------------------------------------------------------------------- /thorp_boards/src/arduino/arduino_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/arduino/arduino_node.cpp -------------------------------------------------------------------------------- /thorp_boards/src/arduino/firmware/arduino/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/arduino/firmware/arduino/Makefile -------------------------------------------------------------------------------- /thorp_boards/src/arduino/firmware/arduino/arduino.ino: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/arduino/firmware/arduino/arduino.ino -------------------------------------------------------------------------------- /thorp_boards/src/arduino/firmware/arduino/setup.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/arduino/firmware/arduino/setup.sh -------------------------------------------------------------------------------- /thorp_boards/src/opencm/firmware/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/firmware/README.md -------------------------------------------------------------------------------- /thorp_boards/src/opencm/firmware/opencm/CM9_BC.cpp.fixed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/firmware/opencm/CM9_BC.cpp.fixed -------------------------------------------------------------------------------- /thorp_boards/src/opencm/firmware/opencm/CM9_BC.h.fixed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/firmware/opencm/CM9_BC.h.fixed -------------------------------------------------------------------------------- /thorp_boards/src/opencm/firmware/opencm/opencm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/firmware/opencm/opencm.h -------------------------------------------------------------------------------- /thorp_boards/src/opencm/firmware/opencm/opencm.ino: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/firmware/opencm/opencm.ino -------------------------------------------------------------------------------- /thorp_boards/src/opencm/ir_ranger.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/ir_ranger.py -------------------------------------------------------------------------------- /thorp_boards/src/opencm/sensors.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_boards/src/opencm/sensors.py -------------------------------------------------------------------------------- /thorp_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_bringup/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/README.md -------------------------------------------------------------------------------- /thorp_bringup/docker/.dockerignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/docker/.dockerignore -------------------------------------------------------------------------------- /thorp_bringup/docker/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/docker/Dockerfile -------------------------------------------------------------------------------- /thorp_bringup/docker/patch_ignition.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/docker/patch_ignition.yaml -------------------------------------------------------------------------------- /thorp_bringup/docker/thorp.rosinstall: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/docker/thorp.rosinstall -------------------------------------------------------------------------------- /thorp_bringup/graveyard/block_gatherer.launch.SIM_APP: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/block_gatherer.launch.SIM_APP -------------------------------------------------------------------------------- /thorp_bringup/graveyard/block_manip.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/block_manip.launch -------------------------------------------------------------------------------- /thorp_bringup/graveyard/block_manip.launch.SIM_APP: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/block_manip.launch.SIM_APP -------------------------------------------------------------------------------- /thorp_bringup/graveyard/block_manip_external.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/block_manip_external.launch -------------------------------------------------------------------------------- /thorp_bringup/graveyard/exec_smach.launch.BAK: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/exec_smach.launch.BAK -------------------------------------------------------------------------------- /thorp_bringup/graveyard/exec_smach.launch.NO_GROUPS: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/exec_smach.launch.NO_GROUPS -------------------------------------------------------------------------------- /thorp_bringup/graveyard/keyboard_ctrl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/keyboard_ctrl.py -------------------------------------------------------------------------------- /thorp_bringup/graveyard/object_manip.launch.BAK: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/object_manip.launch.BAK -------------------------------------------------------------------------------- /thorp_bringup/graveyard/show_tk_fonts.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/show_tk_fonts.py -------------------------------------------------------------------------------- /thorp_bringup/graveyard/thorp_playground.launch.BAK: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/thorp_playground.launch.BAK -------------------------------------------------------------------------------- /thorp_bringup/graveyard/virt_sensor.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/graveyard/virt_sensor.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/calibrate.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/calibrate.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/autodock.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/autodock.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/kinect.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/kinect.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/master_ctrl.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/master_ctrl.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/model.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/model.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/safety_ctrl.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/safety_ctrl.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/senz3d.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/senz3d.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/state_publisher.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/state_publisher.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/includes/xtion.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/includes/xtion.launch.xml -------------------------------------------------------------------------------- /thorp_bringup/launch/moveit.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/moveit.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/navigation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/navigation.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/object_rec.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/object_rec.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/sonar_nav.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/sonar_nav.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/test_arm.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/test_arm.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/thorp_robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/thorp_robot.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/thorp_viz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/thorp_viz.launch -------------------------------------------------------------------------------- /thorp_bringup/launch/view_model.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/launch/view_model.launch -------------------------------------------------------------------------------- /thorp_bringup/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/package.xml -------------------------------------------------------------------------------- /thorp_bringup/param/kinect/depthimage_to_laserscan.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/kinect/depthimage_to_laserscan.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/named_configs/precise_controlling.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/named_configs/precise_controlling.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/named_configs/waypoints_following.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/named_configs/waypoints_following.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/senz3d/calibration.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/senz3d/calibration.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/senz3d/manipulation.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/senz3d/manipulation.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/senz3d/obj_recognition.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/senz3d/obj_recognition.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/vel_multiplexer.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/vel_multiplexer.yaml -------------------------------------------------------------------------------- /thorp_bringup/param/xtion/pointcloud_to_laserscan.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/param/xtion/pointcloud_to_laserscan.yaml -------------------------------------------------------------------------------- /thorp_bringup/rviz/exploration.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/exploration.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/gathering.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/gathering.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/hunting.movie.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/hunting.movie.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/hunting.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/hunting.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/clear.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/clear.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/exit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/exit.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/fold.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/fold.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/reset.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/reset.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/start.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/start.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/icons/stop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/icons/stop.png -------------------------------------------------------------------------------- /thorp_bringup/rviz/manipulation.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/manipulation.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/navigation.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/navigation.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/perception.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/perception.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/user_commands.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/user_commands.yaml -------------------------------------------------------------------------------- /thorp_bringup/rviz/view_all.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/view_all.rviz -------------------------------------------------------------------------------- /thorp_bringup/rviz/view_model.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/rviz/view_model.rviz -------------------------------------------------------------------------------- /thorp_bringup/scripts/aliencontrol.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/scripts/aliencontrol.py -------------------------------------------------------------------------------- /thorp_bringup/scripts/fake_joint_pub.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/scripts/fake_joint_pub.py -------------------------------------------------------------------------------- /thorp_bringup/scripts/fake_servos_srv.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/scripts/fake_servos_srv.py -------------------------------------------------------------------------------- /thorp_bringup/scripts/gripper_cmd.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/scripts/gripper_cmd.py -------------------------------------------------------------------------------- /thorp_bringup/scripts/user_commands.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bringup/scripts/user_commands.py -------------------------------------------------------------------------------- /thorp_bt_cpp/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/cat_hunter.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/cat_hunter.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/exploration.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/exploration.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/explore_house.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/explore_house.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/manipulation.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/manipulation.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/navigation.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/navigation.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/node_models.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/node_models.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/object_gatherer.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/object_gatherer.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/object_manip.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/object_manip.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/patrol_2_points.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/patrol_2_points.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/bt/pickup_objects.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/bt/pickup_objects.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/groot/thorp.btproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/groot/thorp.btproj -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/bt_ros_logger.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/bt_ros_logger.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/bt_runner.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/bt_runner.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/node_register.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/node_register.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/ros_action_node.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/ros_action_node.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/ros_service_node.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/ros_service_node.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/ros_subscriber_node.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/ros_subscriber_node.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/include/thorp_bt_cpp/type_converters.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/include/thorp_bt_cpp/type_converters.hpp -------------------------------------------------------------------------------- /thorp_bt_cpp/launch/bt_runner.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/launch/bt_runner.launch -------------------------------------------------------------------------------- /thorp_bt_cpp/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/package.xml -------------------------------------------------------------------------------- /thorp_bt_cpp/scripts/show_bt_node_on_rviz.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/scripts/show_bt_node_on_rviz.py -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/add_object_to_tray.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/add_object_to_tray.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/cannon_control.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/cannon_control.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_costmaps.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_costmaps.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_gripper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_gripper.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_list.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_list.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_octomap.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_octomap.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_planning_scene.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_planning_scene.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_rail_markers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_rail_markers.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/clear_table_access.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/clear_table_access.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/detect_objects.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/detect_objects.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/detect_tables.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/detect_tables.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/drag_and_drop.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/drag_and_drop.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/exe_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/exe_path.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/expand_pickup_location.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/expand_pickup_location.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/follow_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/follow_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_closest_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_closest_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_from_list.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_from_list.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_list_front.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_list_front.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_path.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_poses_around_table.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_poses_around_table.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/get_robot_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/get_robot_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/go_to_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/go_to_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/list_slicing.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/list_slicing.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/look_at_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/look_at_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/make_pickup_plan.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/make_pickup_plan.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/monitor_objects.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/monitor_objects.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/next_pose_on_tray.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/next_pose_on_tray.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/pickup_object.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/pickup_object.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/place_object.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/place_object.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/plan_room_exploration.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/plan_room_exploration.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/plan_room_sequence.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/plan_room_sequence.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/pop_from_list.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/pop_from_list.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/pose_as_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/pose_as_path.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/push_to_list.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/push_to_list.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/read_ros_param.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/read_ros_param.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/read_user_commands.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/read_user_commands.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/record_pickup_failure.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/record_pickup_failure.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/recovery.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/recovery.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/restore_table_access.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/restore_table_access.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/segment_rooms.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/segment_rooms.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/select_next_target.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/select_next_target.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/set_arm_config.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/set_arm_config.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/set_blackboard.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/set_blackboard.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/smooth_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/smooth_path.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/switch_safety_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/switch_safety_controller.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/table_as_obstacle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/table_as_obstacle.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/track_progress.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/track_progress.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/transform_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/transform_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/actions/use_named_config.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/actions/use_named_config.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/are_same_pose.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/are_same_pose.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/bumper_pressed.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/bumper_pressed.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/camera_fov_clear.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/camera_fov_clear.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/cannon_has_ammo.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/cannon_has_ammo.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/gripper_busy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/gripper_busy.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/in_blackboard.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/in_blackboard.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/is_bool_true.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/is_bool_true.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/is_list_empty.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/is_list_empty.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/object_attached.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/object_attached.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/objects_detected.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/objects_detected.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/table_valid_size.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/table_valid_size.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/table_visited.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/table_visited.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/target_reachable.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/target_reachable.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/conditions/tray_full.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/conditions/tray_full.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/controls/recover_and_retry.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/controls/recover_and_retry.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/decorators/for_each.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/decorators/for_each.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt/decorators/store_result.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt/decorators/store_result.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt_ros_logger.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt_ros_logger.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt_runner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt_runner.cpp -------------------------------------------------------------------------------- /thorp_bt_cpp/src/bt_runner_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_bt_cpp/src/bt_runner_node.cpp -------------------------------------------------------------------------------- /thorp_cannon/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_cannon/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/README.md -------------------------------------------------------------------------------- /thorp_cannon/launch/cannon.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/launch/cannon.launch -------------------------------------------------------------------------------- /thorp_cannon/nodes/cannon_ctrl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/nodes/cannon_ctrl.py -------------------------------------------------------------------------------- /thorp_cannon/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/package.xml -------------------------------------------------------------------------------- /thorp_cannon/scripts/cannon_cmd.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/scripts/cannon_cmd.py -------------------------------------------------------------------------------- /thorp_cannon/src/gazebo_cannon_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_cannon/src/gazebo_cannon_plugin.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_costmap_layers/cfg/SemanticLayer.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/cfg/SemanticLayer.cfg -------------------------------------------------------------------------------- /thorp_costmap_layers/msg/Object.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/msg/Object.msg -------------------------------------------------------------------------------- /thorp_costmap_layers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/package.xml -------------------------------------------------------------------------------- /thorp_costmap_layers/plugins/semantic_layer.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/plugins/semantic_layer.xml -------------------------------------------------------------------------------- /thorp_costmap_layers/scripts/clear_semantic_layer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/scripts/clear_semantic_layer.py -------------------------------------------------------------------------------- /thorp_costmap_layers/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/setup.py -------------------------------------------------------------------------------- /thorp_costmap_layers/src/base_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/base_interface.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/src/semantic_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/semantic_layer.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/src/spatial_hash.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/spatial_hash.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/src/srv_iface_client.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/srv_iface_client.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/src/srv_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/srv_interface.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/src/thorp_costmap_layers/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_costmap_layers/src/thorp_costmap_layers/srv_iface_client.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/thorp_costmap_layers/srv_iface_client.py -------------------------------------------------------------------------------- /thorp_costmap_layers/src/visualization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/src/visualization.cpp -------------------------------------------------------------------------------- /thorp_costmap_layers/srv/QueryObjects.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/srv/QueryObjects.srv -------------------------------------------------------------------------------- /thorp_costmap_layers/srv/UpdateObjects.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/srv/UpdateObjects.srv -------------------------------------------------------------------------------- /thorp_costmap_layers/test/test_semantic_layer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_costmap_layers/test/test_semantic_layer.py -------------------------------------------------------------------------------- /thorp_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_description/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/README.md -------------------------------------------------------------------------------- /thorp_description/config/tray.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/config/tray.yaml -------------------------------------------------------------------------------- /thorp_description/meshes/arm_mount.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/arm_mount.stl -------------------------------------------------------------------------------- /thorp_description/meshes/asus_xtion_pro_live.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/asus_xtion_pro_live.dae -------------------------------------------------------------------------------- /thorp_description/meshes/asus_xtion_pro_live.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/asus_xtion_pro_live.png -------------------------------------------------------------------------------- /thorp_description/meshes/charging_station/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/charging_station/model.config -------------------------------------------------------------------------------- /thorp_description/meshes/charging_station/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/charging_station/model.sdf -------------------------------------------------------------------------------- /thorp_description/meshes/orig_arm_mount.stl: -------------------------------------------------------------------------------- 1 | /home/jorge/catkin_ws/turtlebot/src/turtlebot_arm/turtlebot_arm_description/meshes/mount.stl -------------------------------------------------------------------------------- /thorp_description/meshes/senz3d_mount.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/senz3d_mount.stl -------------------------------------------------------------------------------- /thorp_description/meshes/sonar_array.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/sonar_array.dae -------------------------------------------------------------------------------- /thorp_description/meshes/sonar_array.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/sonar_array.stl -------------------------------------------------------------------------------- /thorp_description/meshes/tray.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/tray.stl -------------------------------------------------------------------------------- /thorp_description/meshes/tray_w_holes.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/tray_w_holes.stl -------------------------------------------------------------------------------- /thorp_description/meshes/xtion_mount.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/xtion_mount.stl -------------------------------------------------------------------------------- /thorp_description/meshes/xtion_mount_a45.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/xtion_mount_a45.stl -------------------------------------------------------------------------------- /thorp_description/meshes/xtion_mount_a45_low.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/meshes/xtion_mount_a45_low.stl -------------------------------------------------------------------------------- /thorp_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/package.xml -------------------------------------------------------------------------------- /thorp_description/scripts/arm_mount.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/scripts/arm_mount.scad -------------------------------------------------------------------------------- /thorp_description/scripts/calc_inertia.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/scripts/calc_inertia.m -------------------------------------------------------------------------------- /thorp_description/scripts/tray.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/scripts/tray.scad -------------------------------------------------------------------------------- /thorp_description/scripts/tubes_poses.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/scripts/tubes_poses.m -------------------------------------------------------------------------------- /thorp_description/scripts/xtion_mount.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/scripts/xtion_mount.scad -------------------------------------------------------------------------------- /thorp_description/urdf/calib: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/calib -------------------------------------------------------------------------------- /thorp_description/urdf/cannon.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/cannon.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/kinect.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/kinect.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/senz3d.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/senz3d.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/standalone_arm.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/standalone_arm.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/thorp.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/thorp.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/thorp.urdf.xacro.senz3d: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/thorp.urdf.xacro.senz3d -------------------------------------------------------------------------------- /thorp_description/urdf/thorp_gazebo.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/thorp_gazebo.urdf.xacro -------------------------------------------------------------------------------- /thorp_description/urdf/xtion.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_description/urdf/xtion.urdf.xacro -------------------------------------------------------------------------------- /thorp_exploration/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_exploration/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/README.md -------------------------------------------------------------------------------- /thorp_exploration/launch/exploration.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/launch/exploration.launch -------------------------------------------------------------------------------- /thorp_exploration/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/package.xml -------------------------------------------------------------------------------- /thorp_exploration/param/room_exploration_kinect.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/param/room_exploration_kinect.yaml -------------------------------------------------------------------------------- /thorp_exploration/param/room_exploration_xtion.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/param/room_exploration_xtion.yaml -------------------------------------------------------------------------------- /thorp_exploration/param/room_segmentation.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/param/room_segmentation.yaml -------------------------------------------------------------------------------- /thorp_exploration/param/room_sequence_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_exploration/param/room_sequence_planning.yaml -------------------------------------------------------------------------------- /thorp_manipulation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_manipulation/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/README.md -------------------------------------------------------------------------------- /thorp_manipulation/graveyard/MOVE_GROUP_pickup_object_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/graveyard/MOVE_GROUP_pickup_object_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/graveyard/MOVE_GROUP_place_object_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/graveyard/MOVE_GROUP_place_object_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/graveyard/has_effort.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/graveyard/has_effort.hpp -------------------------------------------------------------------------------- /thorp_manipulation/launch/includes/arm.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/launch/includes/arm.launch.xml -------------------------------------------------------------------------------- /thorp_manipulation/launch/includes/controllers.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/launch/includes/controllers.launch.xml -------------------------------------------------------------------------------- /thorp_manipulation/launch/manipulation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/launch/manipulation.launch -------------------------------------------------------------------------------- /thorp_manipulation/nodes/dynamixel_joint_state_publisher.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/nodes/dynamixel_joint_state_publisher.py -------------------------------------------------------------------------------- /thorp_manipulation/nodes/dynamixel_relax_all_servos.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/nodes/dynamixel_relax_all_servos.py -------------------------------------------------------------------------------- /thorp_manipulation/nodes/pickup_planner_server.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/nodes/pickup_planner_server.py -------------------------------------------------------------------------------- /thorp_manipulation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/package.xml -------------------------------------------------------------------------------- /thorp_manipulation/param/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/param/controllers.yaml -------------------------------------------------------------------------------- /thorp_manipulation/param/pick_and_place.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/param/pick_and_place.yaml -------------------------------------------------------------------------------- /thorp_manipulation/param/pick_and_place_gazebo.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/param/pick_and_place_gazebo.yaml -------------------------------------------------------------------------------- /thorp_manipulation/scripts/test_arm_ctrl_servers.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/scripts/test_arm_ctrl_servers.py -------------------------------------------------------------------------------- /thorp_manipulation/scripts/test_pickup_object.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/scripts/test_pickup_object.py -------------------------------------------------------------------------------- /thorp_manipulation/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/setup.py -------------------------------------------------------------------------------- /thorp_manipulation/src/house_keeping_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/house_keeping_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/interactive_manip_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/interactive_manip_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/joint_state_watchdog.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/joint_state_watchdog.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/manipulation_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/manipulation_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/move_to_target_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/move_to_target_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/pickup_object_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/pickup_object_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/place_object_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/place_object_server.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/thorp_arm_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/thorp_arm_controller.cpp -------------------------------------------------------------------------------- /thorp_manipulation/src/tray_manager_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_manipulation/src/tray_manager_server.cpp -------------------------------------------------------------------------------- /thorp_mbf_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_mbf_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_mbf_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_mbf_plugins/package.xml -------------------------------------------------------------------------------- /thorp_mbf_plugins/plugins/slow_escape_recovery.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_mbf_plugins/plugins/slow_escape_recovery.xml -------------------------------------------------------------------------------- /thorp_mbf_plugins/src/slow_escape_recovery.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_mbf_plugins/src/slow_escape_recovery.cpp -------------------------------------------------------------------------------- /thorp_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /thorp_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_moveit_config/config/Thorp.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/Thorp.srdf -------------------------------------------------------------------------------- /thorp_moveit_config/config/Thorp_pincher.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/Thorp_pincher.srdf -------------------------------------------------------------------------------- /thorp_moveit_config/config/cartesian_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/cartesian_limits.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/chomp_planning.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/ros_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/ros_controllers.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/config/sensors_3d.yaml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/Thorp_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/Thorp_moveit_sensor_manager.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/chomp_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/demo_gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/demo_gazebo.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/gazebo.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/joystick_control.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /thorp_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/ompl_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/ros_controllers.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /thorp_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /thorp_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_moveit_config/package.xml -------------------------------------------------------------------------------- /thorp_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_msgs/action/DetectObjects.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/DetectObjects.action -------------------------------------------------------------------------------- /thorp_msgs/action/DragAndDrop.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/DragAndDrop.action -------------------------------------------------------------------------------- /thorp_msgs/action/FollowPose.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/FollowPose.action -------------------------------------------------------------------------------- /thorp_msgs/action/MakePickupPlan.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/MakePickupPlan.action -------------------------------------------------------------------------------- /thorp_msgs/action/MoveToTarget.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/MoveToTarget.action -------------------------------------------------------------------------------- /thorp_msgs/action/PickupObject.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/PickupObject.action -------------------------------------------------------------------------------- /thorp_msgs/action/PlaceObject.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/PlaceObject.action -------------------------------------------------------------------------------- /thorp_msgs/action/UserCommand.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/action/UserCommand.action -------------------------------------------------------------------------------- /thorp_msgs/msg/BTNodeStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/BTNodeStatus.msg -------------------------------------------------------------------------------- /thorp_msgs/msg/KeyboardInput.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/KeyboardInput.msg -------------------------------------------------------------------------------- /thorp_msgs/msg/ObjectToPickup.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/ObjectToPickup.msg -------------------------------------------------------------------------------- /thorp_msgs/msg/PickupLocation.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/PickupLocation.msg -------------------------------------------------------------------------------- /thorp_msgs/msg/PickupPlan.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/PickupPlan.msg -------------------------------------------------------------------------------- /thorp_msgs/msg/ThorpError.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/msg/ThorpError.msg -------------------------------------------------------------------------------- /thorp_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/package.xml -------------------------------------------------------------------------------- /thorp_msgs/srv/CannonCommand.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/CannonCommand.srv -------------------------------------------------------------------------------- /thorp_msgs/srv/ClearPlanningScene.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/ClearPlanningScene.srv -------------------------------------------------------------------------------- /thorp_msgs/srv/ConnectWaypoints.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/ConnectWaypoints.srv -------------------------------------------------------------------------------- /thorp_msgs/srv/TrayAddObject.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/TrayAddObject.srv -------------------------------------------------------------------------------- /thorp_msgs/srv/TrayCapacity.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/TrayCapacity.srv -------------------------------------------------------------------------------- /thorp_msgs/srv/TrayNextPose.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_msgs/srv/TrayNextPose.srv -------------------------------------------------------------------------------- /thorp_navigation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_navigation/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/README.md -------------------------------------------------------------------------------- /thorp_navigation/cfg/Follower.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/cfg/Follower.cfg -------------------------------------------------------------------------------- /thorp_navigation/graveyard/custom_move_base.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/custom_move_base.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/global_dynamic_costmap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/global_dynamic_costmap.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/launch/move_base.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/launch/move_base.launch.xml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/launch/move_base_eband.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/launch/move_base_eband.launch.xml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/navigation.launch.smooth_follow: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/navigation.launch.smooth_follow -------------------------------------------------------------------------------- /thorp_navigation/graveyard/nodelet/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/nodelet/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_navigation/graveyard/nodelet/nodes/pose_follower.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/nodelet/nodes/pose_follower.cpp -------------------------------------------------------------------------------- /thorp_navigation/graveyard/nodelet/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/nodelet/package.xml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/nodelet/plugins/nodelets.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/nodelet/plugins/nodelets.xml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/nodelet/pose_follower.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/nodelet/pose_follower.cpp -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/behavior_trees.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/behavior_trees.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/local_planners.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/local_planners.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/move_base/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/move_base/README.md -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/move_base/move_base_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/move_base/move_base_params.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/move_base_flex___.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/move_base_flex___.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/recovery_behaviors.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/recovery_behaviors.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/teb_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/teb_local_planner_params.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/teb_local_planner_params3.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/teb_local_planner_params3.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/param/vel_smoother.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/param/vel_smoother.yaml -------------------------------------------------------------------------------- /thorp_navigation/graveyard/pose_follower.cpp_act_on_pose_cb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/pose_follower.cpp_act_on_pose_cb -------------------------------------------------------------------------------- /thorp_navigation/graveyard/pose_follower.cpp_w_enable_srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/pose_follower.cpp_w_enable_srv -------------------------------------------------------------------------------- /thorp_navigation/graveyard/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/setup.py -------------------------------------------------------------------------------- /thorp_navigation/graveyard/waypoints_path.cpp_DEBUG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/graveyard/waypoints_path.cpp_DEBUG -------------------------------------------------------------------------------- /thorp_navigation/include/thorp_navigation/waypoints_path.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/include/thorp_navigation/waypoints_path.hpp -------------------------------------------------------------------------------- /thorp_navigation/launch/includes/amcl.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/launch/includes/amcl.launch.xml -------------------------------------------------------------------------------- /thorp_navigation/launch/includes/move_base_flex.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/launch/includes/move_base_flex.launch.xml -------------------------------------------------------------------------------- /thorp_navigation/launch/navigation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/launch/navigation.launch -------------------------------------------------------------------------------- /thorp_navigation/maps/dorothy_cafe.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/dorothy_cafe.pgm -------------------------------------------------------------------------------- /thorp_navigation/maps/dorothy_cafe.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/dorothy_cafe.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/edu_room_cropped.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/edu_room_cropped.pgm -------------------------------------------------------------------------------- /thorp_navigation/maps/edu_room_cropped.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/edu_room_cropped.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/empty.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/empty.png -------------------------------------------------------------------------------- /thorp_navigation/maps/empty.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/empty.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/frieburg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/frieburg.png -------------------------------------------------------------------------------- /thorp_navigation/maps/frieburg.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/frieburg.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/fun_house.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/fun_house.png -------------------------------------------------------------------------------- /thorp_navigation/maps/fun_house.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/fun_house.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/graz_home.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/graz_home.pgm -------------------------------------------------------------------------------- /thorp_navigation/maps/graz_home.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/graz_home.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/hospital_section.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/hospital_section.png -------------------------------------------------------------------------------- /thorp_navigation/maps/hospital_section.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/hospital_section.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/maze.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/maze.png -------------------------------------------------------------------------------- /thorp_navigation/maps/maze.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/maze.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/mines.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/mines.png -------------------------------------------------------------------------------- /thorp_navigation/maps/mines.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/mines.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/playground.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/playground.png -------------------------------------------------------------------------------- /thorp_navigation/maps/playground.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/playground.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/robocup.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/robocup.png -------------------------------------------------------------------------------- /thorp_navigation/maps/robocup.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/robocup.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/robopark2.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/robopark2.bmp -------------------------------------------------------------------------------- /thorp_navigation/maps/robopark_plan.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/robopark_plan.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/simple_rooms.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/simple_rooms.png -------------------------------------------------------------------------------- /thorp_navigation/maps/simple_rooms.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/simple_rooms.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/small_house.png: -------------------------------------------------------------------------------- 1 | /home/jorge/catkin_ws/simulation/src/small_house_world/maps/turtlebot3_waffle_pi/map.png -------------------------------------------------------------------------------- /thorp_navigation/maps/small_house.yaml: -------------------------------------------------------------------------------- 1 | /home/jorge/catkin_ws/simulation/src/small_house_world/maps/turtlebot3_waffle_pi/map.yaml -------------------------------------------------------------------------------- /thorp_navigation/maps/sparse_obstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/sparse_obstacles.png -------------------------------------------------------------------------------- /thorp_navigation/maps/sparse_obstacles.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/maps/sparse_obstacles.yaml -------------------------------------------------------------------------------- /thorp_navigation/nodes/mbf_simple_goal_relay.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/nodes/mbf_simple_goal_relay.py -------------------------------------------------------------------------------- /thorp_navigation/nodes/show_velocity.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/nodes/show_velocity.py -------------------------------------------------------------------------------- /thorp_navigation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/package.xml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/common_costmap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/common_costmap.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/dwa_local_planner.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/dwa_local_planner.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/follower_planner.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/follower_planner.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/global_costmap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/global_costmap.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/global_planners.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/global_planners.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/local_costmap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/local_costmap.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/move_base_flex.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/move_base_flex.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/recovery_behaviors.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/recovery_behaviors.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/teb_local_planner.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/teb_local_planner.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/move_base_flex/tro_local_planner.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/move_base_flex/tro_local_planner.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/pose_follower.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/pose_follower.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/vel_smoother.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/vel_smoother.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/vel_smoother_gazebo.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/vel_smoother_gazebo.yaml -------------------------------------------------------------------------------- /thorp_navigation/param/waypoints_path.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/param/waypoints_path.yaml -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_exe_path_and_cancel.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_exe_path_and_cancel.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_get_path_and_cancel.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_get_path_and_cancel.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_get_path_twice.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_get_path_twice.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_move_base_and_cancel.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_move_base_and_cancel.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_move_base_and_exe_path.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_move_base_and_exe_path.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_path_smoother.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_path_smoother.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_path_smoother_n_teb.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_path_smoother_n_teb.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_pose_follower.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_pose_follower.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/call_teb_single_pose_path.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/call_teb_single_pose_path.py -------------------------------------------------------------------------------- /thorp_navigation/scripts/test/spam_exe_path.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/scripts/test/spam_exe_path.py -------------------------------------------------------------------------------- /thorp_navigation/src/pose_follower.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/src/pose_follower.cpp -------------------------------------------------------------------------------- /thorp_navigation/src/pose_servoing.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/src/pose_servoing.cpp -------------------------------------------------------------------------------- /thorp_navigation/src/visual_servoing.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/src/visual_servoing.cpp -------------------------------------------------------------------------------- /thorp_navigation/src/waypoints_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_navigation/src/waypoints_path.cpp -------------------------------------------------------------------------------- /thorp_perception/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_perception/config/cob/object_detection.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/cob/object_detection.yaml -------------------------------------------------------------------------------- /thorp_perception/config/cob/object_projection.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/cob/object_projection.yaml -------------------------------------------------------------------------------- /thorp_perception/config/ork/external.tabletop.detection.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/ork/external.tabletop.detection.ros.ork -------------------------------------------------------------------------------- /thorp_perception/config/ork/linemod.detection.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/ork/linemod.detection.ros.ork -------------------------------------------------------------------------------- /thorp_perception/config/ork/tabletop.detection.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/ork/tabletop.detection.ros.ork -------------------------------------------------------------------------------- /thorp_perception/config/ork/tod.detection.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/ork/tod.detection.ros.ork -------------------------------------------------------------------------------- /thorp_perception/config/rail/segmentation.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/rail/segmentation.yaml -------------------------------------------------------------------------------- /thorp_perception/config/rail/zones.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/config/rail/zones.yaml -------------------------------------------------------------------------------- /thorp_perception/graveyard/experimental.detection.object.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/experimental.detection.object.ros.ork -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/kinect_tabletop.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/kinect_tabletop.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/ork_capture.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/ork_capture.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/ork_softkinetic.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/ork_softkinetic.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/ork_template.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/ork_template.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/ork_track.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/ork_track.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/perception.launch.xml.cob: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/perception.launch.xml.cob -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/perception.launch.xml.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/perception.launch.xml.ork -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/perception.launch.xml.rail: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/perception.launch.xml.rail -------------------------------------------------------------------------------- /thorp_perception/graveyard/launch/ubr1_grasp.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/launch/ubr1_grasp.launch -------------------------------------------------------------------------------- /thorp_perception/graveyard/object_detection_color_HSV.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/object_detection_color_HSV.hpp -------------------------------------------------------------------------------- /thorp_perception/graveyard/object_detection_color_KMEANS.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/object_detection_color_KMEANS.hpp -------------------------------------------------------------------------------- /thorp_perception/graveyard/pick_and_place.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/pick_and_place.py -------------------------------------------------------------------------------- /thorp_perception/graveyard/projection.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/projection.py -------------------------------------------------------------------------------- /thorp_perception/graveyard/rail_object_detection_server.cpp_DIRTY: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/rail_object_detection_server.cpp_DIRTY -------------------------------------------------------------------------------- /thorp_perception/graveyard/senz3d.tabletop.detection.ros.ork: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/graveyard/senz3d.tabletop.detection.ros.ork -------------------------------------------------------------------------------- /thorp_perception/include/thorp_perception/spatial_hash.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/include/thorp_perception/spatial_hash.hpp -------------------------------------------------------------------------------- /thorp_perception/launch/includes/obj_rec.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/launch/includes/obj_rec.launch.xml -------------------------------------------------------------------------------- /thorp_perception/launch/includes/template_matcher.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/launch/includes/template_matcher.launch.xml -------------------------------------------------------------------------------- /thorp_perception/launch/perception.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/launch/perception.launch -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/coke.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/coke.blend -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/coke.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/coke.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/coke.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/coke.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/coke.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/coke.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5.stl.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5.stl.blend -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_blue.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_blue.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_blue.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_blue.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_blue.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_blue.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_green.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_green.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_green.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_green.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_green.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_green.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_red.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_red.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_red.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_red.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_red.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_red.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_red_2.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_red_2.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/cube_2_5_red_2.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/cube_2_5_red_2.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/orbit.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/orbit.blend -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/orbit.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/orbit.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/tower_5.mtl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/tower_5.mtl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/tower_5.obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/tower_5.obj -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/tower_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/tower_5.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/blender/tower_5.stl.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/blender/tower_5.stl.blend -------------------------------------------------------------------------------- /thorp_perception/meshes/circle.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/circle.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/circle.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/circle.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/circle.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/circle.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/clover.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/clover.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/clover.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/clover.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/clover.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/clover.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/cross.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cross.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/cross.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cross.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/cross.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cross.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/cube.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cube.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/cube.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cube.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/cube.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/cube.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/diamond.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/diamond.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/diamond.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/diamond.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/diamond.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/diamond.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/lipstick.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/lipstick.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/lipstick.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/lipstick.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/lipstick.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/lipstick.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/pentagon.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/pentagon.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/pentagon.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/pentagon.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/pentagon.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/pentagon.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/rectangle.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/rectangle.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/rectangle.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/rectangle.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/rectangle.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/rectangle.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/square.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/square.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/square.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/square.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/square.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/square.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/star.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/star.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/star.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/star.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/star.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/star.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/tower.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/tower.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/tower.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/tower.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/tower.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/tower.stl -------------------------------------------------------------------------------- /thorp_perception/meshes/triangle.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/triangle.pcd -------------------------------------------------------------------------------- /thorp_perception/meshes/triangle.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/triangle.ply -------------------------------------------------------------------------------- /thorp_perception/meshes/triangle.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/meshes/triangle.stl -------------------------------------------------------------------------------- /thorp_perception/nodes/object_tracking.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/nodes/object_tracking.py -------------------------------------------------------------------------------- /thorp_perception/nodes/xtion_fov_analyzer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/nodes/xtion_fov_analyzer.py -------------------------------------------------------------------------------- /thorp_perception/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/package.xml -------------------------------------------------------------------------------- /thorp_perception/scripts/generate_meshes.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/scripts/generate_meshes.py -------------------------------------------------------------------------------- /thorp_perception/scripts/generate_meshes.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/scripts/generate_meshes.scad -------------------------------------------------------------------------------- /thorp_perception/scripts/get_object_info_client.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/scripts/get_object_info_client.py -------------------------------------------------------------------------------- /thorp_perception/scripts/parametric_star.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/scripts/parametric_star.scad -------------------------------------------------------------------------------- /thorp_perception/scripts/populate_ork_database.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/scripts/populate_ork_database.py -------------------------------------------------------------------------------- /thorp_perception/src/ork_object_detection_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/src/ork_object_detection_server.cpp -------------------------------------------------------------------------------- /thorp_perception/src/rail_object_detection_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_perception/src/rail_object_detection_server.cpp -------------------------------------------------------------------------------- /thorp_rviz_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_rviz_plugins/icons/classes/CancelNavigationTool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/icons/classes/CancelNavigationTool.png -------------------------------------------------------------------------------- /thorp_rviz_plugins/icons/classes/ClearCostmapTool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/icons/classes/ClearCostmapTool.png -------------------------------------------------------------------------------- /thorp_rviz_plugins/include/thorp_rviz_plugins/button_tool.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/include/thorp_rviz_plugins/button_tool.hpp -------------------------------------------------------------------------------- /thorp_rviz_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/package.xml -------------------------------------------------------------------------------- /thorp_rviz_plugins/plugins.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/plugins.xml -------------------------------------------------------------------------------- /thorp_rviz_plugins/src/button_tool.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/src/button_tool.cpp -------------------------------------------------------------------------------- /thorp_rviz_plugins/src/cancel_navigation_tool.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/src/cancel_navigation_tool.cpp -------------------------------------------------------------------------------- /thorp_rviz_plugins/src/clear_costmap_tool.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_rviz_plugins/src/clear_costmap_tool.cpp -------------------------------------------------------------------------------- /thorp_simulation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_simulation/graveyard/arm_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/arm_control.yaml -------------------------------------------------------------------------------- /thorp_simulation/graveyard/arm_control.yaml__BOOM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/arm_control.yaml__BOOM -------------------------------------------------------------------------------- /thorp_simulation/graveyard/cat_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/cat_house.world -------------------------------------------------------------------------------- /thorp_simulation/graveyard/cat_house_split.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/cat_house_split.world -------------------------------------------------------------------------------- /thorp_simulation/graveyard/fun_house_straight.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/fun_house_straight.png -------------------------------------------------------------------------------- /thorp_simulation/graveyard/fun_house_w_3_tables.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/fun_house_w_3_tables.png -------------------------------------------------------------------------------- /thorp_simulation/graveyard/fun_house_w_outside.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/fun_house_w_outside.png -------------------------------------------------------------------------------- /thorp_simulation/graveyard/gazebo_cannon_plugin.cpp.SPAWN_ROCKET: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/gazebo_cannon_plugin.cpp.SPAWN_ROCKET -------------------------------------------------------------------------------- /thorp_simulation/graveyard/gazebo_ground_truth.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/gazebo_ground_truth.py -------------------------------------------------------------------------------- /thorp_simulation/graveyard/tb3_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/tb3_house.world -------------------------------------------------------------------------------- /thorp_simulation/graveyard/thorp_alica.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/graveyard/thorp_alica.launch -------------------------------------------------------------------------------- /thorp_simulation/launch/includes/sim_common.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/includes/sim_common.launch.xml -------------------------------------------------------------------------------- /thorp_simulation/launch/includes/stdr_relays.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/includes/stdr_relays.launch.xml -------------------------------------------------------------------------------- /thorp_simulation/launch/includes/thorp_gazebo.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/includes/thorp_gazebo.launch.xml -------------------------------------------------------------------------------- /thorp_simulation/launch/navigation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/navigation.launch -------------------------------------------------------------------------------- /thorp_simulation/launch/thorp_gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/thorp_gazebo.launch -------------------------------------------------------------------------------- /thorp_simulation/launch/thorp_stage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/thorp_stage.launch -------------------------------------------------------------------------------- /thorp_simulation/launch/thorp_stdr.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/launch/thorp_stdr.launch -------------------------------------------------------------------------------- /thorp_simulation/nodes/cats_controller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/nodes/cats_controller.py -------------------------------------------------------------------------------- /thorp_simulation/nodes/model_markers.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/nodes/model_markers.py -------------------------------------------------------------------------------- /thorp_simulation/nodes/movie_director.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/nodes/movie_director.py -------------------------------------------------------------------------------- /thorp_simulation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/package.xml -------------------------------------------------------------------------------- /thorp_simulation/param/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/param/controllers.yaml -------------------------------------------------------------------------------- /thorp_simulation/robots/sensors/EZ2_sonar.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/robots/sensors/EZ2_sonar.yaml -------------------------------------------------------------------------------- /thorp_simulation/robots/sensors/GP2Y0A21_ir.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/robots/sensors/GP2Y0A21_ir.yaml -------------------------------------------------------------------------------- /thorp_simulation/robots/thorp.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/robots/thorp.inc -------------------------------------------------------------------------------- /thorp_simulation/robots/thorp.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/robots/thorp.yaml -------------------------------------------------------------------------------- /thorp_simulation/robots/thorp_footprint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/robots/thorp_footprint.png -------------------------------------------------------------------------------- /thorp_simulation/scripts/gazebo_link_state.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/scripts/gazebo_link_state.py -------------------------------------------------------------------------------- /thorp_simulation/scripts/spawn_gazebo_models.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/scripts/spawn_gazebo_models.py -------------------------------------------------------------------------------- /thorp_simulation/src/gazebo_camera_control.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/src/gazebo_camera_control.cpp -------------------------------------------------------------------------------- /thorp_simulation/src/gazebo_camera_control_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/src/gazebo_camera_control_plugin.cpp -------------------------------------------------------------------------------- /thorp_simulation/src/gazebo_ground_truth.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/src/gazebo_ground_truth.cpp -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/empty.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/empty.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/fun_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/fun_house.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/camera_control/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/camera_control/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cat_black/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cat_black/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cat_black/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cat_black/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cat_orange/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cat_orange/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cat_orange/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cat_orange/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/circle/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/circle/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/circle/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/circle/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/circle/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/circle.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/clover/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/clover/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/clover/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/clover/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/clover/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/clover.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/coke/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/coke/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/coke/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/coke/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/coke/model.stl: -------------------------------------------------------------------------------- 1 | /home/jorge/catkin_ws/thorp/src/thorp/thorp_perception/meshes/blender/coke.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cross/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cross/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cross/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cross/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cross/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/cross.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/cube.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube_20k/model-1_2.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube_20k/model-1_2.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube_20k/model-1_3.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube_20k/model-1_3.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube_20k/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube_20k/model-1_4.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube_20k/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube_20k/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/cube_20k/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/cube_20k/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/diamond/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/diamond/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/diamond/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/diamond/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/diamond/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/diamond.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/doll_table/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/doll_table/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/doll_table/model.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/doll_table/model.dae -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/doll_table/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/doll_table/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/doll_table/model.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/doll_table/model.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/dumpster/model-1_3.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/dumpster/model-1_3.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/dumpster/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/dumpster/model-1_4.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/dumpster/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/dumpster/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/dumpster/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/dumpster/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/jersey_barrier/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/jersey_barrier/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table/model.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table/model.scad -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table/model.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table/model.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table_x15/model.scad: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table_x15/model.scad -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table_x15/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table_x15/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lack_table_x15/model.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lack_table_x15/model.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lipstick/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lipstick/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lipstick/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/lipstick/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/lipstick/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/lipstick.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/mailbox/model-1_3.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/mailbox/model-1_3.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/mailbox/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/mailbox/model-1_4.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/mailbox/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/mailbox/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/mailbox/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/mailbox/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/pentagon/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/pentagon/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/pentagon/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/pentagon/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/pentagon/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/pentagon.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/rectangle/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/rectangle/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/rectangle/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/rectangle/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/rectangle/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/rectangle.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/rocket/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/rocket/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/rocket/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/rocket/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/square/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/square/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/square/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/square/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/square/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/square.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/star/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/star/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/star/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/star/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/star/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/star.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/templates/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/templates/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/templates/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/templates/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/tower/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/tower/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/tower/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/tower/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/tower/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/tower.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/triangle/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/triangle/model.config -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/triangle/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/triangle/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/triangle/model.stl: -------------------------------------------------------------------------------- 1 | ../../../../../thorp_perception/meshes/triangle.stl -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/models/wood_cube_2_5cm/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/models/wood_cube_2_5cm/model.sdf -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/playground.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/gazebo/playground.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/gazebo/small_house.world: -------------------------------------------------------------------------------- 1 | /home/jorge/catkin_ws/simulation/src/small_house_world/worlds/small_house.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/blocks.inc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/blocks.inc -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/empty.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/empty.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/fun_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/fun_house.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/maze.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/maze.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/robopark_plan.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/robopark_plan.world -------------------------------------------------------------------------------- /thorp_simulation/worlds/stage/small_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_simulation/worlds/stage/small_house.world -------------------------------------------------------------------------------- /thorp_smach/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_smach/graveyard/CATKIN_IGNORE: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/graveyard/block_gatherer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/block_gatherer.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/block_manip.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/block_manip.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/block_transport.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/block_transport.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/calibration_tools/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/graveyard/calibration_tools/actuator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/calibration_tools/actuator.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/calibration_tools/msg_imports.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/calibration_tools/msg_imports.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/config.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/config.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/find_object.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/find_object.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/korus_move_arm_planner_ik.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/korus_move_arm_planner_ik.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/move_arm_ik.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/move_arm_ik.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/move_arm_planner.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/move_arm_planner.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/move_arm_planner_ik.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/move_arm_planner_ik.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/move_things_around.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/move_things_around.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/patrol.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/patrol.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/pick_object.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/pick_object.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/pick_object_manual.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/pick_object_manual.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/launch/place_object.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/launch/place_object.launch -------------------------------------------------------------------------------- /thorp_smach/graveyard/manipulation.py_w_viz_obj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/manipulation.py_w_viz_obj -------------------------------------------------------------------------------- /thorp_smach/graveyard/monitor_tables_w_cb.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/monitor_tables_w_cb.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/object_manip.py_CONC: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/object_manip.py_CONC -------------------------------------------------------------------------------- /thorp_smach/graveyard/object_manip.py_LOOP: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/object_manip.py_LOOP -------------------------------------------------------------------------------- /thorp_smach/graveyard/object_manip.py_NEW: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/object_manip.py_NEW -------------------------------------------------------------------------------- /thorp_smach/graveyard/object_manip.py_NOWRAP: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/object_manip.py_NOWRAP -------------------------------------------------------------------------------- /thorp_smach/graveyard/object_manip_tbarm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/object_manip_tbarm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/old_tray_states.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/old_tray_states.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/perception.py.w_block_detection: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/perception.py.w_block_detection -------------------------------------------------------------------------------- /thorp_smach/graveyard/pick_and_place_tools/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/graveyard/pick_and_place_tools/ik.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/pick_and_place_tools/ik.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/pick_and_place_tools/misc_tools.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/pick_and_place_tools/misc_tools.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/pick_and_place_tools/move_arm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/pick_and_place_tools/move_arm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/pick_and_place_tools/msg_imports.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/pick_and_place_tools/msg_imports.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/calibration/arm_calibration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/calibration/arm_calibration.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/calibration/head_calibration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/calibration/head_calibration.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/manipulation/move_arm_ik_as.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/manipulation/move_arm_ik_as.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/manipulation/move_gripper_as.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/manipulation/move_gripper_as.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/manipulation/pick_object_as.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/manipulation/pick_object_as.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/manipulation/place_object_as.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/manipulation/place_object_as.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/scripts/test/add_collision_object.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/scripts/test/add_collision_object.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/segment_rooms_w_img.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/segment_rooms_w_img.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/arm_calibration_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/arm_calibration_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/find_object_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/find_object_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/find_table_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/find_table_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/head_calibration_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/head_calibration_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/move_arm_ik_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/move_arm_ik_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/move_arm_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/move_arm_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/pick_object_manual_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/pick_object_manual_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/pick_object_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/pick_object_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/place_object_manual_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/place_object_manual_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/place_object_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/place_object_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/prepare_ik_seeds_sm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/prepare_ik_seeds_sm.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/state_machines/state_machines_imports.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/state_machines/state_machines_imports.py -------------------------------------------------------------------------------- /thorp_smach/graveyard/transformer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/graveyard/transformer.py -------------------------------------------------------------------------------- /thorp_smach/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/package.xml -------------------------------------------------------------------------------- /thorp_smach/scripts/run_look_to_pose_state.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/scripts/run_look_to_pose_state.py -------------------------------------------------------------------------------- /thorp_smach/scripts/show_state_on_rviz.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/scripts/show_state_on_rviz.py -------------------------------------------------------------------------------- /thorp_smach/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/setup.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/cat_hunter.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/cat_hunter.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/containers/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/containers/do_on_exit.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/containers/do_on_exit.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/explore_house.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/explore_house.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/object_gatherer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/object_gatherer.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/object_manip.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/object_manip.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/patrol_2_points.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/patrol_2_points.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/pickup_objects.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/pickup_objects.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/stack_all_cubes.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/stack_all_cubes.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/cannon_ctrl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/cannon_ctrl.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/common.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/common.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/costmaps.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/costmaps.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/exploration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/exploration.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/gathering.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/gathering.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/geometry.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/geometry.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/manipulation.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/manipulation.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/navigation.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/navigation.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/perception.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/perception.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/pickup_objs.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/pickup_objs.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/semantics.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/semantics.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/states/userdata.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/states/userdata.py -------------------------------------------------------------------------------- /thorp_smach/src/thorp_smach/utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_smach/src/thorp_smach/utils.py -------------------------------------------------------------------------------- /thorp_toolkit/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/CMakeLists.txt -------------------------------------------------------------------------------- /thorp_toolkit/graveyard/UpdateCollisionObjs.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/graveyard/UpdateCollisionObjs.srv -------------------------------------------------------------------------------- /thorp_toolkit/graveyard/geometry_2d.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/graveyard/geometry_2d.cpp -------------------------------------------------------------------------------- /thorp_toolkit/graveyard/geometry_2d.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/graveyard/geometry_2d.hpp -------------------------------------------------------------------------------- /thorp_toolkit/graveyard/semantic_layer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/graveyard/semantic_layer.py -------------------------------------------------------------------------------- /thorp_toolkit/graveyard/test_semantic_layer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/graveyard/test_semantic_layer.py -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/alternative_config.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/alternative_config.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/common.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/common.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/geometry.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/geometry.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/kobuki_base.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/kobuki_base.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/math.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/math.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/parameters.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/parameters.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/planning_scene.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/planning_scene.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/progress_tracker.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/progress_tracker.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/reconfigure.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/reconfigure.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/simulation.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/simulation.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/spatial_hash.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/spatial_hash.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/tf2.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/tf2.hpp -------------------------------------------------------------------------------- /thorp_toolkit/include/thorp_toolkit/visualization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/include/thorp_toolkit/visualization.hpp -------------------------------------------------------------------------------- /thorp_toolkit/nodes/save_pose_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/nodes/save_pose_node.cpp -------------------------------------------------------------------------------- /thorp_toolkit/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/package.xml -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/common.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/common.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/decorators.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/decorators.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/geometry.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/geometry.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/planning_scene.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/planning_scene.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/point_tracker.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/point_tracker.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/progress_tracker.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/progress_tracker.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/reconfigure.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/reconfigure.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/semantic_map.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/semantic_map.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/singleton.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/singleton.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/spatial_hash.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/spatial_hash.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/tachometer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/tachometer.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/transform.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/transform.py -------------------------------------------------------------------------------- /thorp_toolkit/python/thorp_toolkit/visualization.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/python/thorp_toolkit/visualization.py -------------------------------------------------------------------------------- /thorp_toolkit/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/setup.py -------------------------------------------------------------------------------- /thorp_toolkit/src/alternative_config.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/alternative_config.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/common.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/common.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/geometry.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/geometry.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/kobuki_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/kobuki_base.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/planning_scene.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/planning_scene.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/progress_tracker.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/progress_tracker.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/reconfigure.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/reconfigure.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/simulation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/simulation.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/tf2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/tf2.cpp -------------------------------------------------------------------------------- /thorp_toolkit/src/visualization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/src/visualization.cpp -------------------------------------------------------------------------------- /thorp_toolkit/test/test_progress_tracker.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/test/test_progress_tracker.py -------------------------------------------------------------------------------- /thorp_toolkit/test/test_reconfigure.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/test/test_reconfigure.py -------------------------------------------------------------------------------- /thorp_toolkit/test/test_semantic_map.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/corot/thorp/HEAD/thorp_toolkit/test/test_semantic_map.py --------------------------------------------------------------------------------