commit e3894ca3f9dd02811d347324346a675b7e299827 Author: yikestone Date: Sun May 27 22:08:36 2018 +0530 initial diff --git a/line_follower_description/.model.config b/line_follower_description/.model.config new file mode 100644 index 0000000..fe90178 --- /dev/null +++ b/line_follower_description/.model.config @@ -0,0 +1,13 @@ + + + line_follower + 1.0 + urdf/line_follower.urdf + + yikestone + name@email.address + + + A description of the model + + diff --git a/line_follower_description/CMakeLists.txt b/line_follower_description/CMakeLists.txt new file mode 100644 index 0000000..6763170 --- /dev/null +++ b/line_follower_description/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(line_follower_description) +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + roscpp + rviz + tf + urdf + xacro +) +include_directories( +${catkin_INCLUDE_DIRS} +) diff --git a/line_follower_description/config/line_follower_config.yaml b/line_follower_description/config/line_follower_config.yaml new file mode 100644 index 0000000..3662e6b --- /dev/null +++ b/line_follower_description/config/line_follower_config.yaml @@ -0,0 +1,16 @@ +line_follower: + # Publish all joint states ----------------------------------- + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + + + # Effort Controllers --------------------------------------- + leftWheel_effort_controller: + type: effort_controllers/JointEffortController + joint: left_wheel_hinge + pid: {p: 100.0, i: 0.1, d: 10.0} + rightWheel_effort_controller: + type: effort_controllers/JointEffortController + joint: right_wheel_hinge + pid: {p: 100.0, i: 0.1, d: 10.0} diff --git a/line_follower_description/launch/line_follower_robot.launch b/line_follower_description/launch/line_follower_robot.launch new file mode 100644 index 0000000..509db73 --- /dev/null +++ b/line_follower_description/launch/line_follower_robot.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/line_follower_description/meshes/caster_wheel.stl b/line_follower_description/meshes/caster_wheel.stl new file mode 100644 index 0000000..8106741 Binary files /dev/null and b/line_follower_description/meshes/caster_wheel.stl differ diff --git a/line_follower_description/package.xml b/line_follower_description/package.xml new file mode 100644 index 0000000..8b5e83b --- /dev/null +++ b/line_follower_description/package.xml @@ -0,0 +1,23 @@ + + + line_follower_description + 0.0.0 + The line_follower_description package + yikes + TODO + catkin + geometry_msgs + roscpp + rviz + tf + urdf + xacro + geometry_msgs + roscpp + rviz + tf + urdf + xacro + + + diff --git a/line_follower_description/urdf.rviz b/line_follower_description/urdf.rviz new file mode 100644 index 0000000..655f882 --- /dev/null +++ b/line_follower_description/urdf.rviz @@ -0,0 +1,194 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 330 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bottom_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + elbow_pitch_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + elbow_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + gripper_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + gripper_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_aft_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_pitch_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_pitch_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 1.12009 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.138732 + Y: -0.0432205 + Z: 0.292796 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.230398 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.425398 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 611 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000013c000001d9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000001d9000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000001d9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000001d9000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004c00000003efc0100000002fb0000000800540069006d00650100000000000004c0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000269000001d900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1216 + X: 43 + Y: 14 diff --git a/line_follower_description/urdf.vcg b/line_follower_description/urdf.vcg new file mode 100644 index 0000000..cd9e661 --- /dev/null +++ b/line_follower_description/urdf.vcg @@ -0,0 +1,44 @@ +Background\ ColorR=0.0941176 +Background\ ColorG=0 +Background\ ColorB=0.466667 +Fixed\ Frame=/base_link +Target\ Frame= +Grid.Alpha=0.5 +Grid.Cell\ Size=0.5 +Grid.ColorR=0.898039 +Grid.ColorG=0.898039 +Grid.ColorB=0.898039 +Grid.Enabled=1 +Grid.Line\ Style=0 +Grid.Line\ Width=0.03 +Grid.Normal\ Cell\ Count=0 +Grid.OffsetX=0 +Grid.OffsetY=0 +Grid.OffsetZ=0 +Grid.Plane=0 +Grid.Plane\ Cell\ Count=10 +Grid.Reference\ Frame= +Robot\ Model.Alpha=1 +Robot\ Model.Collision\ Enabled=0 +Robot\ Model.Enabled=1 +Robot\ Model.Robot\ Description=robot_description +Robot\ Model.TF\ Prefix= +Robot\ Model.Update\ Interval=0 +Robot\ Model.Visual\ Enabled=1 +Robot\:\ Robot\ Model\ Link\ base_linkShow\ Axes=0 +Robot\:\ Robot\ Model\ Link\ base_linkShow\ Trail=0 +Robot\:\ Robot\ Model\ Link\ legShow\ Axes=0 +Robot\:\ Robot\ Model\ Link\ legShow\ Trail=0 +Tool\ 2D\ Nav\ GoalTopic=goal +Tool\ 2D\ Pose\ EstimateTopic=initialpose +Camera\ Type=rviz::OrbitViewController +Camera\ Config=1.15779 3.76081 2.16475 0 0 0 +Property\ Grid\ State=selection=.Global StatusTopStatus;expanded=.Global Options,Grid.Enabled,Robot Model.Enabled;scrollpos=0,0;splitterpos=150,285;ispageselected=1 +[Display0] +Name=Grid +Package=rviz +ClassName=rviz::GridDisplay +[Display1] +Name=Robot Model +Package=rviz +ClassName=rviz::RobotModelDisplay diff --git a/line_follower_description/urdf/line_follower.gazebo b/line_follower_description/urdf/line_follower.gazebo new file mode 100644 index 0000000..4b02a47 --- /dev/null +++ b/line_follower_description/urdf/line_follower.gazebo @@ -0,0 +1,84 @@ + + + + + + /line_follower + + + + + + true + false + 100 + left_wheel_hinge + right_wheel_hinge + ${chassisWidth+wheelWidth} + ${2*wheelRadius} + 20 + line_follower/cmd_vel + true + 1 + line_follower/odom_diffdrive + true + odom + true + 1 + footprint + + + + + + map + chassis + line_follower/odom + 30.0 + + + + + Gazebo/Orange + + + + 0.0 + 0.0 + Gazebo/Grey + + + + Gazebo/Grey + + 30.0 + + 1.3962634 + + 800 + 800 + R8G8B8 + + + 0.02 + 300 + + + + true + 0.0 + line_follower/camera1 + image_raw + camera_info + camera_link + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + diff --git a/line_follower_description/urdf/line_follower.urdf b/line_follower_description/urdf/line_follower.urdf new file mode 100644 index 0000000..c6c7c9c --- /dev/null +++ b/line_follower_description/urdf/line_follower.urdf @@ -0,0 +1,270 @@ + + + + + + + + + /line_follower + + + + + true + false + 100 + left_wheel_hinge + right_wheel_hinge + 0.25 + 0.2 + 20 + line_follower/cmd_vel + true + 1 + line_follower/odom_diffdrive + true + odom + true + 1 + footprint + + + + + map + chassis + line_follower/odom + 30.0 + + + + Gazebo/Orange + + + 0.0 + 0.0 + Gazebo/Grey + + + Gazebo/Grey + + 30.0 + + 1.3962634 + + 800 + 800 + R8G8B8 + + + 0.02 + 300 + + + + true + 0.0 + line_follower/camera1 + image_raw + camera_info + camera_link + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + EffortJointInterface + 10 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + EffortJointInterface + 10 + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/line_follower_description/urdf/line_follower.xacro b/line_follower_description/urdf/line_follower.xacro new file mode 100644 index 0000000..02676ab --- /dev/null +++ b/line_follower_description/urdf/line_follower.xacro @@ -0,0 +1,119 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/line_follower_description/urdf/macros.xacro b/line_follower_description/urdf/macros.xacro new file mode 100644 index 0000000..e7e9d9f --- /dev/null +++ b/line_follower_description/urdf/macros.xacro @@ -0,0 +1,78 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + EffortJointInterface + 10 + + + + + diff --git a/line_follower_description/urdf/materials.xacro b/line_follower_description/urdf/materials.xacro new file mode 100644 index 0000000..311c3cd --- /dev/null +++ b/line_follower_description/urdf/materials.xacro @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/line_follower_gazebo/CMakeLists.txt b/line_follower_gazebo/CMakeLists.txt new file mode 100644 index 0000000..c7dfa29 --- /dev/null +++ b/line_follower_gazebo/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 2.8.3) +project(line_follower_gazebo) + +find_package(catkin REQUIRED COMPONENTS + roscpp + gazebo_ros +) + +find_package(gazebo REQUIRED) + +catkin_package( +DEPENDS + roscpp + gazebo_ros +) + +link_directories(${GAZEBO_LIBRARY_DIRS}) +include_directories(${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS}) +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) +#add_library(${PROJECT_NAME} src/simple_world_plugin.cpp) +#target_link_libraries(${catkin_LIBRARIES}) + diff --git a/line_follower_gazebo/launch/line_follower.launch b/line_follower_gazebo/launch/line_follower.launch new file mode 100644 index 0000000..261b253 --- /dev/null +++ b/line_follower_gazebo/launch/line_follower.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/line_follower_gazebo/package.xml b/line_follower_gazebo/package.xml new file mode 100644 index 0000000..ab2a19f --- /dev/null +++ b/line_follower_gazebo/package.xml @@ -0,0 +1,54 @@ + + + line_follower_gazebo + 0.0.0 + The line_follower_gazebo package + + + + + yikes + + TODO + + roscpp + roscpp + gazebo_ros + gazebo_ros + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + diff --git a/line_follower_gazebo/worlds/line.world b/line_follower_gazebo/worlds/line.world new file mode 100644 index 0000000..86f191e --- /dev/null +++ b/line_follower_gazebo/worlds/line.world @@ -0,0 +1,12 @@ + + + + + model://sun + + + model://path + 0 0 0 0 0 0 + + +