Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,10 +84,9 @@ And add the previous line to the end of your file. Same procedure if you use zsh
To Save press Cntrl+O , Enter . Cntrl+X to exit

# Ackerman dependencies
sudo apt install ros-noetic-ros-controllers
sudo apt-get install ros-noetic-ackermann-msgs
sudo apt-get install ros-noetic-ros-controllers ros-noetic-ackermann-msgs

# Launch woth ackerman
# Launch with ackerman
roslaunch ackermann_vehicle_gazebo ackermann_robot_with_arena_conversion.launch

# Running the simulation enviroment
Expand Down
4 changes: 2 additions & 2 deletions cnn/launch/write.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<arg name="image_raw_topic" default="/ackermann_vehicle/camera/rgb/image_raw"/>
<arg name="twist_cmd_topic" default="/cmd_vel"/>
<arg name="bool_cmd_topic" default=""/>
<arg name="vel_cmd_topic" default=""/>
<arg name="folder" default="set1"/>
<arg name="rate" default="30"/>
<arg name="width" default="320"/>
Expand All @@ -11,7 +11,7 @@
<node name="cnn_write" pkg="cnn" type="write.py" output="screen" required="true">
<param name="image_raw_topic" value="$(arg image_raw_topic)"/>
<param name="twist_cmd_topic" value="$(arg twist_cmd_topic)"/>
<param name="bool_cmd_topic" value="$(arg bool_cmd_topic)"/>
<param name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<param name="folder" value="$(arg folder)"/>
<param name="rate" value="$(arg rate)"/>
<param name="width" value="$(arg width)"/>
Expand Down
6 changes: 3 additions & 3 deletions cnn/scripts/write.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ def main():

image_raw_topic = rospy.get_param('~image_raw_topic', '/ackermann_vehicle/camera/rgb/image_raw')
twist_cmd_topic = rospy.get_param('~twist_cmd_topic', '/cmd_vel')
bool_cmd_topic = rospy.get_param('~bool_cmd_topic', '')
vel_cmd_topic = rospy.get_param('~vel_cmd_topic', '')
base_folder = rospy.get_param('~folder', 'set1')
rate_hz = rospy.get_param('~rate', 30)
image_width = rospy.get_param('~width', 320)
Expand All @@ -128,11 +128,11 @@ def main():
# Subscribe topics
# If we have a bool topic, we are recording the linear variable as the boolean.
# If not, we are recording the linear velocity from the twist
if bool_cmd_topic != "":
if vel_cmd_topic != "":
# Define angular as 0 to prevent errors when we give velocity first instead of angle
angular = 0
rospy.Subscriber(twist_cmd_topic, Twist, messageRealReceivedCallback)
rospy.Subscriber(bool_cmd_topic, Bool, boolReceivedCallback)
rospy.Subscriber(vel_cmd_topic, Bool, boolReceivedCallback)
else:
rospy.Subscriber(twist_cmd_topic, Twist, messageReceivedCallback)

Expand Down
1 change: 1 addition & 0 deletions physical_bringup/launch/modules/android_conversor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="108"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="bool_btn_topic" default="/android_input_velin"/>

<include file="$(find robot_driving)/launch/physical_robot_control.launch">
<arg name="twist_dir_topic" value="$(arg twist_dir_topic)"/>
Expand Down
4 changes: 2 additions & 2 deletions physical_bringup/launch/modules/write_cnn.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<arg name="image_raw_topic" default="/real_camera"/>
<arg name="twist_cmd_topic" default="/android_input_dir"/>
<arg name="bool_cmd_topic" default="/android_input_vel"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="folder" default="set1"/>
<arg name="rate" default="30"/>
<arg name="width" default="320"/>
Expand All @@ -11,7 +11,7 @@
<include file="$(find cnn)/launch/write.launch">
<arg name="image_raw_topic" value="$(arg image_raw_topic)"/>
<arg name="twist_cmd_topic" value="$(arg twist_cmd_topic)"/>
<arg name="bool_cmd_topic" value="$(arg bool_cmd_topic)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<arg name="folder" value="$(arg folder)"/>
<arg name="rate" value="$(arg rate)"/>
<arg name="width" value="$(arg width)"/>
Expand Down
6 changes: 3 additions & 3 deletions physical_bringup/launch/traxxas_drive_signal1.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="int_dir_topic" default="/pub_dir"/>
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="125"/>
<arg name="bool_vel_topic" default="/android_input_vel"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>

<arg name="camera_topic" default="/real_camera"/>
<arg name="int_camera_id" default="2"/>
Expand All @@ -23,12 +23,12 @@
<arg name="twist_linear_x" value="$(arg twist_linear_x)"/>
</include>

<include file="$(find physical_bringup)/launch/android_conversor.launch">
<include file="$(find physical_bringup)/launch/modules/android_conversor.launch">
<arg name="twist_dir_topic" value="$(arg twist_dir_topic)"/>
<arg name="int_dir_topic" value="$(arg int_dir_topic)"/>
<arg name="int_vel_topic" value="$(arg int_vel_topic)"/>
<arg name="int_vel_max" value="$(arg int_vel_max)"/>
<arg name="bool_vel_topic" value="$(arg bool_vel_topic)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
</include>

<include file="$(find physical_bringup)/launch/modules/lane_camera.launch">
Expand Down
10 changes: 5 additions & 5 deletions physical_bringup/launch/traxxas_drive_write.launch
Original file line number Diff line number Diff line change
@@ -1,25 +1,25 @@
<launch>

<arg name="folder" default="set1"/>
<arg name="twist_cmd_topic" default="/android_input_dir"/>
<arg name="twist_dir_topic" default="/android_input_dir"/>
<arg name="bool_cmd_topic" default="/android_input_vel"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="int_dir_topic" default="/pub_dir"/>
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="102"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="bool_btn_topic" default="/android_input_velin"/>

<arg name="camera_topic" default="/real_camera"/>
<arg name="int_camera_id" default="2"/>

<include file="$(find physical_bringup)/launch/modules/rosserial.launch" />
<include file="$(find physical_bringup)/launch/modules/rosserial.launch" />

<include file="$(find physical_bringup)/launch/modules/android_conversor.launch">
<arg name="twist_dir_topic" value="$(arg twist_dir_topic)"/>
<arg name="int_dir_topic" value="$(arg int_dir_topic)"/>
<arg name="int_vel_topic" value="$(arg int_vel_topic)"/>
<arg name="int_vel_max" value="$(arg int_vel_max)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<arg name="bool_btn_topic" value="$(arg bool_btn_topic)"/>
</include>

<!--<include file="$(find physical_bringup)/launch/modules/usb_cam.launch" />-->
Expand All @@ -31,7 +31,7 @@

<include file="$(find simulation_bringup)/launch/modules/write_cnn.launch" >
<arg name="twist_cmd_topic" value="$(arg twist_cmd_topic)"/>
<arg name="bool_cmd_topic" value="$(arg bool_cmd_topic)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<arg name="image_raw_topic" value="$(arg camera_topic)"/>
<arg name="folder" value="$(arg folder)"/>
</include>
Expand Down
40 changes: 21 additions & 19 deletions physical_bringup/launch/traxxas_free_drive.launch
Original file line number Diff line number Diff line change
@@ -1,26 +1,28 @@
<launch>
<arg name="twist_dir_topic" default="/android_input_dir"/>
<arg name="int_dir_topic" default="/pub_dir"/>
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="108"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="twist_dir_topic" default="/android_input_dir"/>
<arg name="int_dir_topic" default="/pub_dir"/>
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="108"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="bool_btn_topic" default="/android_input_velin"/>

<arg name="camera_topic" default="/real_camera"/>
<arg name="int_camera_id" default="2"/>
<arg name="camera_topic" default="/real_camera"/>
<arg name="int_camera_id" default="2"/>

<include file="$(find physical_bringup)/launch/modules/rosserial.launch" />
<include file="$(find physical_bringup)/launch/modules/rosserial.launch" />

<include file="$(find physical_bringup)/launch/modules/android_conversor.launch">
<arg name="twist_dir_topic" value="$(arg twist_dir_topic)"/>
<arg name="int_dir_topic" value="$(arg int_dir_topic)"/>
<arg name="int_vel_topic" value="$(arg int_vel_topic)"/>
<arg name="int_vel_max" value="$(arg int_vel_max)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
</include>
<include file="$(find physical_bringup)/launch/modules/android_conversor.launch">
<arg name="twist_dir_topic" value="$(arg twist_dir_topic)"/>
<arg name="int_dir_topic" value="$(arg int_dir_topic)"/>
<arg name="int_vel_topic" value="$(arg int_vel_topic)"/>
<arg name="int_vel_max" value="$(arg int_vel_max)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<arg name="bool_btn_topic" value="$(arg bool_btn_topic)"/>
</include>

<include file="$(find physical_bringup)/launch/modules/lane_camera.launch">
<arg name="camera_topic" value="$(arg camera_topic)"/>
<arg name="int_camera_id" value="$(arg int_camera_id)"/>
</include>
<include file="$(find physical_bringup)/launch/modules/lane_camera.launch">
<arg name="camera_topic" value="$(arg camera_topic)"/>
<arg name="int_camera_id" value="$(arg int_camera_id)"/>
</include>

</launch>
2 changes: 2 additions & 0 deletions robot_driving/launch/physical_robot_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
<arg name="int_vel_topic" default="/pub_vel"/>
<arg name="int_vel_max" default="108"/>
<arg name="vel_cmd_topic" default="/android_input_vel"/>
<arg name="bool_btn_topic" default="/android_input_velin"/>



<node name="robot_driving" pkg="robot_driving" type="AndroidConversor.py" output="screen">
Expand Down
41 changes: 35 additions & 6 deletions robot_driving/scripts/AndroidConversor.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,10 @@
# Global Variables
global PubDir
global PubVel
global PubBool
global ma1, ma2, ba1, ba2
global bool_vel



# Direction Callback Function
Expand All @@ -28,14 +31,31 @@ def messageReceivedCallbackDir(message):
#Publicar mensagens
PubDir.publish(int(AngleOut))


# Velocity Callback Function
def messageReceivedCallbackBtn(message):

global bool_vel

bool_button = message.data

# If the button is pressed, bool_vel switches from True to False and viceversa
if bool_button:
bool_vel = not bool_vel

PubBool.publish(bool_vel)


# Velocity Callback Function
def messageReceivedCallbackVel(message):

bool = message.data
global vel_max
global vel_center

bool_cmd = message.data

# If the button is pressed, the velocity is max, if it's not, it's null
if bool:
#If android_input_vel is true, velocity is max. If not, velocity is zero

if bool_cmd:
vel = vel_max
else:
vel = vel_center
Expand All @@ -52,15 +72,22 @@ def main():

global PubDir
global PubVel
global PubBool
global ma1, ma2, ba1, ba2
global vel_max, vel_center
global bool_vel

#Define initial variable
bool_vel = False


# Initiates the node
rospy.init_node('AndroidConversor', anonymous=False)

# Get parameters
twist_dir_topic = rospy.get_param('~twist_dir_topic', '/android_input_dir')
bool_vel_topic = rospy.get_param('~bool_vel_topic', '/android_input_vel')
vel_cmd_topic = rospy.get_param('~vel_cmd_topic', '/android_input_vel')
bool_btn_topic = rospy.get_param('~bool_btn_topic', '/android_input_velin')
int_dir_topic = rospy.get_param('~int_dir_topic', '/pub_dir')
int_vel_topic = rospy.get_param('~int_vel_topic', '/pub_vel')
int_vel_max = rospy.get_param('~int_vel_max', 108)
Expand All @@ -71,8 +98,10 @@ def main():

PubDir = rospy.Publisher(int_dir_topic, Int16, queue_size=10)
PubVel = rospy.Publisher(int_vel_topic, Int16, queue_size=10)
PubBool = rospy.Publisher(vel_cmd_topic, Bool, queue_size=10)
rospy.Subscriber(twist_dir_topic, Twist, messageReceivedCallbackDir)
rospy.Subscriber(bool_vel_topic, Bool, messageReceivedCallbackVel)
rospy.Subscriber(vel_cmd_topic, Bool, messageReceivedCallbackVel)
rospy.Subscriber(bool_btn_topic, Bool, messageReceivedCallbackBtn)

#Angle

Expand Down
4 changes: 2 additions & 2 deletions simulation_bringup/launch/modules/write_cnn.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<arg name="image_raw_topic" default="/ackermann_vehicle/camera/rgb/image_raw"/>
<arg name="twist_cmd_topic" default="/cmd_vel"/>
<arg name="bool_cmd_topic" default=""/>
<arg name="vel_cmd_topic" default=""/>
<arg name="folder" default="set1"/>
<arg name="rate" default="30"/>
<arg name="width" default="320"/>
Expand All @@ -11,7 +11,7 @@
<include file="$(find cnn)/launch/write.launch">
<arg name="image_raw_topic" value="$(arg image_raw_topic)"/>
<arg name="twist_cmd_topic" value="$(arg twist_cmd_topic)"/>
<arg name="bool_cmd_topic" value="$(arg bool_cmd_topic)"/>
<arg name="vel_cmd_topic" value="$(arg vel_cmd_topic)"/>
<arg name="folder" value="$(arg folder)"/>
<arg name="rate" value="$(arg rate)"/>
<arg name="width" value="$(arg width)"/>
Expand Down