Skip to content

Commit

Permalink
Revert "Minor release v0.1.1"
Browse files Browse the repository at this point in the history
This reverts commit dba2cf3.
  • Loading branch information
AbdelrahmanElsaidElsawy committed Sep 21, 2022
1 parent dba2cf3 commit 32f9cbf
Show file tree
Hide file tree
Showing 6 changed files with 68 additions and 73 deletions.
7 changes: 3 additions & 4 deletions beamng_control/launch/example.launch
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
<launch>
<arg name="scenario" default="west_coast_with_no_sensors" doc="[utah_scenario_with_lidar,utah_scenario_with_cam,utah_with_all_sensors, simple_scenario,simple_scenario_no_sensors, simple_scenario_pickup,simple_scenario_with_lidar,simple_scenario_cam, west_coast_with_electrics, west_coast_with_imu,west_coast_with_electrics_and_lidar, west_coast_with_lidar,weather,west_coast_with_sensors, west_coast_with_ultrasonic,west_coast_with_time,west_coast_with_damage,west_coast_with_gforce,west_coast_with_no_sensors,west_scenario_with_cam, west_coast_with_all_sensors]"/>
<arg name="scenario" default="west_coast_with_imu" doc="[west_coast_with_damage,west_coast_with_electrics, west_coast_with_imu, west_coast_with_lidar]"/>
<include file="$(find beamng_control)/launch/bridge.launch">
<!-- substitute with the ip address of your target machine-->
<arg name="host" value="192.168.1.107"/>
<!-- <arg name="host" value="192.168.46.57"/> -->
<arg name="host" value="192.168.34.88"/>
<!-- choose scenario-->
<arg name="scenario_config" value="$(find beamng_control)/config/scenarios/$(arg scenario).json"/>
</include>
</launch>
</launch>
2 changes: 1 addition & 1 deletion beamng_control/scripts/beamng_control/bridge.py
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ def main():
f' version is {available_version}, aborting process.')
sys.exit(1)

# bngpy.setup_logging()
bngpy.setup_logging()

argv = rospy.myargv(argv=sys.argv)
rospy.loginfo("cmd args"+str(argv))
Expand Down
6 changes: 3 additions & 3 deletions beamng_control/scripts/beamng_control/publishers.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import std_msgs.msg

import beamngpy.sensors as bng_sensors
#from beamngpy.noise import RandomImageNoise, RandomLIDARNoise
from beamngpy.noise import RandomImageNoise, RandomLIDARNoise

from visualization_msgs.msg import Marker, MarkerArray

Expand All @@ -27,8 +27,8 @@ def get_sensor_publisher(sensor):
bng_sensors.Electrics: ElectricsPublisher,
bng_sensors.Camera: CameraPublisher,
bng_sensors.Lidar: LidarPublisher,
# RandomImageNoise: CameraPublisher,
#s RandomLIDARNoise: LidarPublisher
RandomImageNoise: CameraPublisher,
RandomLIDARNoise: LidarPublisher
}
for k, v in sensor_mapping.items():
if isinstance(sensor, k):
Expand Down
2 changes: 1 addition & 1 deletion beamng_control/scripts/beamng_control/sensorHelper.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
import copy

import beamngpy.sensors as bng_sensors
#from beamngpy.noise import RandomImageNoise, RandomLIDARNoise
from beamngpy.noise import RandomImageNoise, RandomLIDARNoise


class SensorSpecificationError(TypeError):
Expand Down
114 changes: 60 additions & 54 deletions beamng_teleop_keyboard/nodes/converter
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
from logging import exception
import rospy
from geometry_msgs.msg import Twist
from std_msgs.msg import String
import subprocess
import os
import beamngpy as bngpy
Expand All @@ -14,8 +13,6 @@ class twist2bng():
def __init__(self):
self.BNG_pub = rospy.Publisher('/control', VehicleControl ,queue_size=10)
self.cmd_vel_sub = rospy.Subscriber( '/cmd_vel', Twist, self.cmd_vel_callback , queue_size=10 )
self.brake_sub = rospy.Subscriber( '/brake', String, self.brake_callback , queue_size=10 )
# self.brake_sub = rospy.Subscriber( '/brake', String, self.brake_callback , queue_size=10 )
#set puplish rate
self.checker_rate = rospy.Rate(10)
self.Vehicle_Control_msg=VehicleControl()
Expand All @@ -26,16 +23,11 @@ class twist2bng():
self.control_linear_vel=0
self.control_angular_vel=0
self.has_velosity=False
self.brake_state="False"
self.vehicle_state="initial"
self.main_loop()

# ------------- call back functions ---------------- #


def brake_callback(self, brake_state):
self.brake_state=brake_state.data
# print ("brake_state", self.brake_state)

def cmd_vel_callback(self, cmd_vel):
# self.has_velosity= cmd_vel
self.control_linear_vel_new= cmd_vel.linear.x
Expand All @@ -44,20 +36,22 @@ class twist2bng():

def twist_msg_comparison(self):
if self.control_linear_vel_old != self.control_linear_vel_new:
# print ("new data")
self.convert_cmd_to_bng(self.control_linear_vel_new,self.control_angular_vel_new)
# print ("new reading")
print ("new data")
self.control_linear_vel_old = self.control_linear_vel_new
self.convert_cmd_to_bng(self.control_linear_vel_new,self.control_angular_vel_new)
return True


if self.control_angular_vel_old != self.control_angular_vel_new:
# print ("new data")
self.convert_cmd_to_bng(self.control_linear_vel_new,self.control_angular_vel_new)
# print ("new reading")
print ("new data")
self.control_angular_vel_old = self.control_angular_vel_new
self.convert_cmd_to_bng(self.control_linear_vel_new,self.control_angular_vel_new)
return True

else:
# print ("old data")
print ("old data")
return False


Expand All @@ -67,47 +61,58 @@ class twist2bng():


def convert_cmd_to_bng(self,control_linear_vel,control_angular_vel):
self.Vehicle_Control_msg=VehicleControl()
# print ("inside convert_cmd_to_bng")
# print ("",control_linear_vel)
if self.brake_state=="True":
self.Vehicle_Control_msg.throttle = 0.0
self.Vehicle_Control_msg.steering = 0.0
self.Vehicle_Control_msg.brake = 1
self.Vehicle_Control_msg.parkingbrake = 1
self.Vehicle_Control_msg.clutch = 1
self.Vehicle_Control_msg.gear = 1
self.vehicle_state="stop"
# print ("",self.vehicle_state)

if self.brake_state=="False":
if control_linear_vel < 0.0:
self.Vehicle_Control_msg.throttle = abs(control_linear_vel)
self.Vehicle_Control_msg.steering = control_angular_vel
self.Vehicle_Control_msg.brake = 0
self.Vehicle_Control_msg.parkingbrake = 0
self.Vehicle_Control_msg.clutch = 0
self.Vehicle_Control_msg.gear = -1
self.vehicle_state="reverse"
# print ("",self.vehicle_state)

else:
self.Vehicle_Control_msg.throttle = abs(control_linear_vel)
self.Vehicle_Control_msg.steering = control_angular_vel
self.Vehicle_Control_msg.brake = 0
self.Vehicle_Control_msg.parkingbrake = 0
self.Vehicle_Control_msg.clutch = 0
self.Vehicle_Control_msg.gear = 1
self.vehicle_state="go"
print ("",self.vehicle_state)
print ("",self.brake_state)




self.Vehicle_Control_msg=VehicleControl()

if control_linear_vel == 0.0 :
self.Vehicle_Control_msg.throttle = 0.0
self.Vehicle_Control_msg.steering = 0.0
self.Vehicle_Control_msg.brake = 1
self.Vehicle_Control_msg.parkingbrake = 1
self.Vehicle_Control_msg.clutch = 1
self.Vehicle_Control_msg.gear = 0

if control_linear_vel < 0.0 :
self.Vehicle_Control_msg.throttle = abs(control_linear_vel)
self.Vehicle_Control_msg.steering = control_angular_vel
self.Vehicle_Control_msg.brake = 0
self.Vehicle_Control_msg.parkingbrake = 0
self.Vehicle_Control_msg.clutch = 0
self.Vehicle_Control_msg.gear = -1


else :
self.Vehicle_Control_msg.throttle = abs(control_linear_vel)
self.Vehicle_Control_msg.steering = control_angular_vel
self.Vehicle_Control_msg.brake = 0
self.Vehicle_Control_msg.parkingbrake = 0
self.Vehicle_Control_msg.clutch = 0
self.Vehicle_Control_msg.gear = 1

# print ("",self.Vehicle_Control_msg)
# self.BNG_pub.publish(self.Vehicle_Control_msg)


def move_from_terminal(self):
command= "rostopic pub -r 1 control beamng_msgs/VehicleControl "
throttle= self.Vehicle_Control_msg.throttle
steering= self.Vehicle_Control_msg.steering
brake= self.Vehicle_Control_msg.brake
parkingbrake= self.Vehicle_Control_msg.parkingbrake
clutch= self.Vehicle_Control_msg.clutch
gear= self.Vehicle_Control_msg.gear
combine = command + str(steering) + " " + str(throttle) + " " + str(brake) + " " + str(parkingbrake) + " " + str(clutch) + " " + str(gear)
# subprocess.run([combine], universal_newlines=True, shell=True)
try:
print ("calling terminal")
print ("" , combine)
cp = subprocess.run([combine], universal_newlines=False, shell=False)
except :
print(" ------------------")
print(" ------------------")
print(" bridge error")
print(" ------------------")
print(" ------------------")




Expand All @@ -117,8 +122,9 @@ class twist2bng():
# print(self.twist_msg_comparison)
if self.twist_msg_comparison:
self.BNG_pub.publish(self.Vehicle_Control_msg)

# print("",self.vehicle_state)
# self.move_from_terminal()
# else:

self.checker_rate.sleep()


Expand Down
10 changes: 0 additions & 10 deletions beamng_teleop_keyboard/nodes/teleop_key
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

import rospy
from geometry_msgs.msg import Twist
from std_msgs.msg import String

import sys, select, os
if os.name == 'nt':
import msvcrt
Expand Down Expand Up @@ -105,7 +103,6 @@ if __name__=="__main__":

rospy.init_node('teleop')
pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)
brakepub = rospy.Publisher('brake', String, queue_size=10)
# BNG_pub = rospy.Publisher('control', bng_msgs.VehicleControl ,queue_size=10)
# BNG_pub = rospy.Publisher('control', VehicleControl ,queue_size=10)
# BNG_pub = rospy.Publisher('control', BNG_msgs,queue_size=2)
Expand All @@ -117,7 +114,6 @@ if __name__=="__main__":
target_angular_vel = 0.0
control_linear_vel = 0.0
control_angular_vel = 0.0
brake_state= "False"

try:
print(msg)
Expand All @@ -127,29 +123,24 @@ if __name__=="__main__":
target_linear_vel = checkLinearLimitVelocity(target_linear_vel + LIN_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
brake_state= "False"
elif key == 'x' :
target_linear_vel = checkLinearLimitVelocity(target_linear_vel - LIN_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
brake_state= "False"
elif key == 'd' :
target_angular_vel = checkAngularLimitVelocity(target_angular_vel + ANG_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
brake_state= "False"
elif key == 'a' :
target_angular_vel = checkAngularLimitVelocity(target_angular_vel - ANG_VEL_STEP_SIZE)
status = status + 1
print(vels(target_linear_vel,target_angular_vel))
brake_state= "False"
elif key == ' ' or key == 's' :
target_linear_vel = 0.0
control_linear_vel = 0.0
target_angular_vel = 0.0
control_angular_vel = 0.0
print(vels(target_linear_vel, target_angular_vel))
brake_state= "True"
else:
if (key == '\x03'):
break
Expand All @@ -167,7 +158,6 @@ if __name__=="__main__":
twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = control_angular_vel

pub.publish(twist)
brakepub.publish(brake_state)

except:
print(e)
Expand Down

0 comments on commit 32f9cbf

Please sign in to comment.