-
Notifications
You must be signed in to change notification settings - Fork 12
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #200 from rubennc91/master
Added the project for the paper related with sim FPGA
- Loading branch information
Showing
65 changed files
with
6,856 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,32 @@ | ||
|
||
### Prepare ROS WorkSpace | ||
mkdir paper_simfpga_ws | ||
cd paper_simfpga_ws | ||
mkdir src | ||
cd src | ||
catkin_create_pkg diffdrive_cam_bot std_msgs rospy roscpp | ||
Copy the sources from paper_ros_ws to my directory source of the package. Include the turtlebot2_urdf_model folder. | ||
|
||
(opt) cp -r * ~/catkin_ws/src/ | ||
cd .. (paper_simfpga_ws) | ||
catkin_make | ||
roscd diffdrive_cam_turtlebot to check | ||
roslaunch diffdrive_cam_bot main.launch | ||
|
||
### Prepare Verilator workspace | ||
Copy the workspace from paper_verilator_ws in a place. | ||
|
||
cd paper_verilator_ws | ||
make | ||
##### Check the PoC verilator simFPGA | ||
./obj_dir/Vdesign_top | ||
|
||
### Start it up all together: | ||
- Terminal 1: Launch ROS (`roscore`) | ||
- Terminal 2: Launch PoC verilator simFPGA (`./obj_dir/Vdesign_top`) | ||
- Terminal 3: Launch Gazebo environment (`roslaunch diffdrive_cam_bot main.launch`) | ||
|
||
### Possible bug fixes | ||
source /opt/ros/noetic/setup.bash | ||
source ~/catkin_ws/devel/setup.bash | ||
roslaunch diffdrive_cam_bot main.launch |
34 changes: 34 additions & 0 deletions
34
sim_fpga/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/CMakeLists.txt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
project(diffdrive_cam_bot) | ||
|
||
## Find catkin macros and libraries | ||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) | ||
## is used, also find other catkin packages | ||
find_package(catkin REQUIRED COMPONENTS) | ||
|
||
find_package(gazebo REQUIRED) | ||
|
||
catkin_package() | ||
|
||
include_directories(${GAZEBO_INCLUDE_DIRS}) | ||
|
||
add_library(personplugin plugins/person.cc) | ||
|
||
target_link_libraries(personplugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES}) | ||
|
||
install(TARGETS personplugin | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
) | ||
|
||
install(DIRECTORY | ||
models | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
) | ||
|
||
install(DIRECTORY launch | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
) | ||
|
||
|
||
|
||
|
5 changes: 5 additions & 0 deletions
5
sim_fpga/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/README
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,5 @@ | ||
roslaunch diffdrive_cam_bot main.launch | ||
|
||
rostopic pub -1 /cmd_vel geometry_msgs/Twist -- '[0.2, 0.0, 0.0]' '[0.0, 0.0, 0.1]' | ||
|
||
in Gazebo 9, you can click on "View" and then activate "Collisions" to see the robot. |
11 changes: 11 additions & 0 deletions
11
sim_fpga/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/build.sh
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
#!/usr/bin/env bash | ||
mkdir build | ||
export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:$PWD/build | ||
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:$PWD/models | ||
cd build | ||
rm -rf * | ||
cmake ../ | ||
make | ||
cd ~/catkin_ws | ||
catkin build diffdrive_cam_bot | ||
cd - |
27 changes: 27 additions & 0 deletions
27
...a/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/launch/follow_person.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,27 @@ | ||
<?xml version="1.0"?> | ||
<launch> | ||
<rosparam command="load" file="$(find follow_person)/config/sim.conf" /> | ||
|
||
<arg name="world" default="$(find follow_person)/worlds/follow_person.world"/> | ||
|
||
<include file="$(find drone_wrapper)/launch/mavros_px4_sitl.launch"> | ||
<arg name="world" value="$(arg world)"/> | ||
<arg name="Y" value="1.57"/> | ||
</include> | ||
|
||
<!-- Image Post-processed--> | ||
<arg name="image_yolo" default="/brain/yolo_output/image_raw"/> | ||
<arg name="image_cmd" default="/brain/cmd_response/image_raw"/> | ||
|
||
<!-- | ||
<node name="image_view_yolo" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_yolo)"/> | ||
</node> | ||
<node name="image_view_cmd" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_cmd)"/> | ||
</node> | ||
--> | ||
|
||
<arg name="perspective" default="$(find follow_person)/perspectives/follow_person.perspective"/> | ||
<node name="rqt_gui" pkg="rqt_gui" type="rqt_gui" respawn="false" output="screen" args="--perspective-file $(arg perspective)"/> | ||
</launch> |
34 changes: 34 additions & 0 deletions
34
...GA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/launch/follow_person_turtlebot.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
<?xml version="1.0"?> | ||
<launch> | ||
<!--<rosparam command="load" file="$(find follow_person)/config/sim.conf" />--> | ||
|
||
<arg name="world" default="$(find diffdrive_cam_bot)/worlds/follow_person.world"/> | ||
<include file="$(find gazebo_ros)/launch/empty_world.launch"> | ||
<arg name="world_name" value="$(arg world)"/> | ||
<arg name="paused" value="false"/> | ||
<arg name="use_sim_time" value="true"/> | ||
<arg name="gui" value="true"/> | ||
<arg name="recording" value="false"/> | ||
<arg name="debug" value="false"/> | ||
</include> | ||
<include file="$(find turtlebot2_urdf_model)/launch/spawn_robot.launch"> | ||
</include> | ||
|
||
<!-- Image Post-processed--> | ||
<arg name="image_yolo" default="/brain/yolo_output/image_raw"/> | ||
<arg name="image_cmd" default="/brain/cmd_response/image_raw"/> | ||
|
||
<!-- | ||
<node name="image_view_yolo" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_yolo)"/> | ||
</node> | ||
<node name="image_view_cmd" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_cmd)"/> | ||
</node> | ||
--> | ||
<?ignore | ||
<arg name="perspective" default="$(find follow_person)/perspectives/follow_person.perspective"/> | ||
<node name="rqt_gui" pkg="rqt_gui" type="rqt_gui" respawn="false" output="screen" args="--perspective-file $(arg perspective)"/> | ||
?> | ||
|
||
</launch> |
47 changes: 47 additions & 0 deletions
47
sim_fpga/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/launch/main.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,47 @@ | ||
<?xml version="1.0"?> | ||
<launch> | ||
<!--<rosparam command="load" file="$(find follow_person)/config/sim.conf" />--> | ||
|
||
<!--<arg name="world_name" value="$(arg world)"/>--> | ||
<arg name="paused" value="false"/> | ||
<arg name="use_sim_time" value="true"/> | ||
<arg name="gui" value="true"/> | ||
<arg name="headless" default="false"/> | ||
<arg name="debug" value="false"/> | ||
|
||
<env name="GAZEBO_MODEL_PATH" value="$(find diffdrive_cam_bot)/models:$(optenv GAZEBO_MODEL_PATH)"/> | ||
<env name="GAZEBO_RESOURCE_PATH" value="$(find diffdrive_cam_bot)/worlds:$(optenv GAZEBO_RESOURCE_PATH)"/> | ||
|
||
|
||
<include file="$(find gazebo_ros)/launch/empty_world.launch"> | ||
<arg name="world_name" default="$(find diffdrive_cam_bot)/worlds/follow_person.world"/> | ||
<arg name="paused" value="$(arg paused)"/> | ||
<arg name="use_sim_time" value="$(arg use_sim_time)"/> | ||
<arg name="gui" value="$(arg gui)"/> | ||
<arg name="headless" value="$(arg headless)"/> | ||
<arg name="debug" value="$(arg debug)"/> | ||
</include> | ||
|
||
<include file="$(find turtlebot2_urdf_model)/launch/spawn_robot.launch"> | ||
</include> | ||
|
||
<!-- Image Post-processed--> | ||
<arg name="image_yolo" default="/brain/yolo_output/image_raw"/> | ||
<arg name="image_cmd" default="/brain/cmd_response/image_raw"/> | ||
|
||
<!-- | ||
<node name="image_view_yolo" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_yolo)"/> | ||
</node> | ||
<node name="image_view_cmd" pkg="image_view" type="image_view"> | ||
<remap from="image" to="$(arg image_cmd)"/> | ||
</node> | ||
--> | ||
<?ignore | ||
<arg name="perspective" default="$(find follow_person)/perspectives/follow_person.perspective"/> | ||
<node name="rqt_gui" pkg="rqt_gui" type="rqt_gui" respawn="false" output="screen" args="--perspective-file $(arg perspective)"/> | ||
?> | ||
|
||
</launch> | ||
|
||
|
11 changes: 11 additions & 0 deletions
11
...a/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/models/RedBall/model.config
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
<?xml version="1.0" ?> | ||
<model> | ||
<name>RedBall</name> | ||
<version>1.0</version> | ||
<sdf version="1.7">model.sdf</sdf> | ||
<author> | ||
<name></name> | ||
<email></email> | ||
</author> | ||
<description></description> | ||
</model> |
130 changes: 130 additions & 0 deletions
130
...fpga/paper-FPGA_Robotics-sim-FPGA/paper_ros_ws/diffdrive_cam_bot/models/RedBall/model.sdf
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,130 @@ | ||
<?xml version='1.0'?> | ||
<sdf version='1.7'> | ||
<model name='RedBall'> | ||
<link name='link_0'> | ||
<inertial> | ||
<mass>3979.35</mass> | ||
<inertia> | ||
<ixx>397.935</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>397.935</iyy> | ||
<iyz>0</iyz> | ||
<izz>397.935</izz> | ||
</inertia> | ||
<pose>0 0 0 0 -0 0</pose> | ||
</inertial> | ||
<pose>0 0 0 0 -0 0</pose> | ||
<gravity>1</gravity> | ||
<self_collide>0</self_collide> | ||
<kinematic>0</kinematic> | ||
<enable_wind>0</enable_wind> | ||
<visual name='visual'> | ||
<pose>0 0 0 0 -0 0</pose> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
<material> | ||
<lighting>1</lighting> | ||
<script> | ||
<uri>file://media/materials/scripts/gazebo.material</uri> | ||
<name>Gazebo/Red</name> | ||
</script> | ||
<shader type='pixel'> | ||
<normal_map>__default__</normal_map> | ||
</shader> | ||
<ambient>1 0 0 1</ambient> | ||
<diffuse>1 0 0 1</diffuse> | ||
<specular>0.1 0.1 0.1 1</specular> | ||
<emissive>0 0 0 1</emissive> | ||
</material> | ||
<transparency>0</transparency> | ||
<cast_shadows>1</cast_shadows> | ||
</visual> | ||
<visual name='ModelPreview_0::link_0::visual_1'> | ||
<pose>0 0 0 0 -0 0</pose> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
<material> | ||
<lighting>1</lighting> | ||
<script> | ||
<uri>file://media/materials/scripts/gazebo.material</uri> | ||
<name>Gazebo/Red</name> | ||
</script> | ||
<shader type='pixel'> | ||
<normal_map>__default__</normal_map> | ||
</shader> | ||
<ambient>1 0 0 1</ambient> | ||
<diffuse>1 0 0 1</diffuse> | ||
<specular>0.1 0.1 0.1 1</specular> | ||
<emissive>0 0 0 1</emissive> | ||
</material> | ||
<transparency>0</transparency> | ||
<cast_shadows>1</cast_shadows> | ||
</visual> | ||
<collision name='collision'> | ||
<laser_retro>0</laser_retro> | ||
<max_contacts>0</max_contacts> | ||
<pose>0 0 0 0 -0 0</pose> | ||
<geometry> | ||
<sphere> | ||
<radius>0.75</radius> | ||
</sphere> | ||
</geometry> | ||
<surface> | ||
<friction> | ||
<ode> | ||
<mu>1</mu> | ||
<mu2>1</mu2> | ||
<fdir1>0 0 0</fdir1> | ||
<slip1>0</slip1> | ||
<slip2>0</slip2> | ||
</ode> | ||
<torsional> | ||
<coefficient>1</coefficient> | ||
<patch_radius>0</patch_radius> | ||
<surface_radius>0</surface_radius> | ||
<use_patch_radius>1</use_patch_radius> | ||
<ode> | ||
<slip>0</slip> | ||
</ode> | ||
</torsional> | ||
</friction> | ||
<bounce> | ||
<restitution_coefficient>0</restitution_coefficient> | ||
<threshold>1e+06</threshold> | ||
</bounce> | ||
<contact> | ||
<collide_without_contact>0</collide_without_contact> | ||
<collide_without_contact_bitmask>1</collide_without_contact_bitmask> | ||
<collide_bitmask>1</collide_bitmask> | ||
<ode> | ||
<soft_cfm>0</soft_cfm> | ||
<soft_erp>0.2</soft_erp> | ||
<kp>1e+13</kp> | ||
<kd>1</kd> | ||
<max_vel>0.01</max_vel> | ||
<min_depth>0</min_depth> | ||
</ode> | ||
<bullet> | ||
<split_impulse>1</split_impulse> | ||
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold> | ||
<soft_cfm>0</soft_cfm> | ||
<soft_erp>0.2</soft_erp> | ||
<kp>1e+13</kp> | ||
<kd>1</kd> | ||
</bullet> | ||
</contact> | ||
</surface> | ||
</collision> | ||
</link> | ||
<plugin name="personplugin" filename="libpersonplugin.so"/> | ||
<static>0</static> | ||
<allow_auto_disable>1</allow_auto_disable> | ||
</model> | ||
</sdf> |
Oops, something went wrong.