Skip to content
20 changes: 12 additions & 8 deletions examples/tools/pybullet_linear_tire_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,14 @@
import matplotlib.pyplot as plt
import numpy as np

from smarts.core.chassis import AckermannChassis
from smarts.bullet import pybullet
from smarts.bullet.chassis import BulletAckermannChassis
from smarts.bullet.pybullet import bullet_client as bc
from smarts.core.controllers.actuator_dynamic_controller import (
ActuatorDynamicController,
ActuatorDynamicControllerState,
)
from smarts.core.coordinates import Heading, Pose
from smarts.core.utils import pybullet
from smarts.core.utils.pybullet import bullet_client as bc
from smarts.core.vehicle import Vehicle

TIMESTEP_SEC = 1 / 240
Expand Down Expand Up @@ -165,7 +165,7 @@ def run(client, vehicle, plane_body_id, sliders, n_steps=1e6):

client.stepSimulation()

frictions_ = frictions(sliders)
frictions_ = frictions(client, sliders)

if prev_friction_sum is not None and not math.isclose(
sum(frictions_.values()), prev_friction_sum
Expand All @@ -188,7 +188,7 @@ def run(client, vehicle, plane_body_id, sliders, n_steps=1e6):
)


def frictions(sliders):
def frictions(client, sliders):
return dict(
lateralFriction=client.readUserDebugParameter(sliders["lateral_friction"]),
spinningFriction=client.readUserDebugParameter(sliders["spinning_friction"]),
Expand All @@ -201,7 +201,7 @@ def frictions(sliders):
)


if __name__ == "__main__":
def main():
# https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html
# mp.set_start_method('spawn', force=True)

Expand Down Expand Up @@ -242,12 +242,12 @@ def frictions(sliders):
path = str(path.absolute())
plane_body_id = client.loadURDF(path, useFixedBase=True)

client.changeDynamics(plane_body_id, -1, **frictions(sliders))
client.changeDynamics(plane_body_id, -1, **frictions(client, sliders))

pose = pose = Pose.from_center((0, 0, 0), Heading(0))
vehicle = Vehicle(
"hello",
chassis=AckermannChassis(
chassis=BulletAckermannChassis(
pose=pose,
bullet_client=client,
tire_parameters_filepath="../../smarts/core/models/tire_parameters.yaml",
Expand Down Expand Up @@ -311,3 +311,7 @@ def frictions(sliders):
plt.plot(time, yaw)

plt.show()


if __name__ == "__main__":
main()
16 changes: 10 additions & 6 deletions examples/tools/pybullet_sumo_orientation_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,13 @@

import numpy as np

from smarts.bullet import pybullet
from smarts.bullet.chassis import BulletBoxChassis
from smarts.bullet.pybullet import bullet_client as bc
from smarts.core.actor import ActorRole
from smarts.core.chassis import BoxChassis
from smarts.core.coordinates import Heading, Pose
from smarts.core.scenario import Scenario
from smarts.core.sumo_traffic_simulation import SumoTrafficSimulation
from smarts.core.utils import pybullet
from smarts.core.utils.pybullet import bullet_client as bc
from smarts.core.vehicle import VEHICLE_CONFIGS, Vehicle
from smarts.core.vehicle_state import VehicleState

Expand Down Expand Up @@ -96,7 +96,7 @@ def run(
current_provider_state = traffic_sim.step(None, 0.01, step * 0.01)
for pose, i in zip(injected_poses, range(len(injected_poses))):
converted_to_provider = VehicleState(
vehicle_id=f"EGO{i}",
actor_id=f"EGO{i}",
vehicle_config_type="passenger",
pose=pose,
dimensions=passenger_dimen,
Expand All @@ -115,7 +115,7 @@ def run(
pose = Pose.from_center([0, 0, 0], Heading(0))
vehicles[v_id] = Vehicle(
id=v_id,
chassis=BoxChassis(
chassis=BulletBoxChassis(
pose=pose,
speed=0,
dimensions=vehicle_config.dimensions,
Expand Down Expand Up @@ -144,7 +144,7 @@ def run(
# pytype: enable=name-error


if __name__ == "__main__":
def main():
# https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html
# mp.set_start_method('spawn', force=True)

Expand Down Expand Up @@ -181,3 +181,7 @@ def run(
plane_body_id,
n_steps=int(1e6),
)


if __name__ == "__main__":
main()
26 changes: 12 additions & 14 deletions examples/tools/pybullet_trajectory_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,14 @@

import matplotlib.pyplot as plt

from smarts.core.chassis import AckermannChassis
from smarts.bullet import pybullet
from smarts.bullet.chassis import BulletAckermannChassis
from smarts.bullet.pybullet import bullet_client as bc
from smarts.core.controllers import (
TrajectoryTrackingController,
TrajectoryTrackingControllerState,
)
from smarts.core.coordinates import Heading, Pose
from smarts.core.utils import pybullet
from smarts.core.utils.pybullet import bullet_client as bc
from smarts.core.vehicle import Vehicle

TIMESTEP_SEC = 1 / 240
Expand Down Expand Up @@ -79,18 +79,12 @@ def run(client, vehicle, plane_body_id, sliders, n_steps=1e6):
vehicle,
controller_state,
dt_sec=TIMESTEP_SEC,
heading_gain=0.05,
lateral_gain=0.65,
velocity_gain=1.8,
traction_gain=2,
derivative_activation=False,
speed_reduction_activation=False,
)

client.stepSimulation()
vehicle.sync_chassis()

frictions_ = frictions(sliders)
frictions_ = frictions(client, sliders)

if prev_friction_sum is not None and not math.isclose(
sum(frictions_.values()), prev_friction_sum
Expand All @@ -112,7 +106,7 @@ def run(client, vehicle, plane_body_id, sliders, n_steps=1e6):
ydes.append(trajectory[1][0])


def frictions(sliders):
def frictions(client, sliders):
return dict(
throttle=client.addUserDebugParameter("Throttle", 0, 1, 0.0),
brake=client.addUserDebugParameter("Brake", 0, 1, 0),
Expand All @@ -128,7 +122,7 @@ def frictions(sliders):
)


if __name__ == "__main__":
def main():
# https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html
# mp.set_start_method('spawn', force=True)

Expand Down Expand Up @@ -166,12 +160,12 @@ def frictions(sliders):
path = str(path.absolute())
plane_body_id = client.loadURDF(path, useFixedBase=True)

client.changeDynamics(plane_body_id, -1, **frictions(sliders))
client.changeDynamics(plane_body_id, -1, **frictions(client, sliders))
pose = pose = Pose.from_center((0, 0, 0), Heading(0))

vehicle = Vehicle(
id="vehicle",
chassis=AckermannChassis(
chassis=BulletAckermannChassis(
pose=pose,
bullet_client=client,
),
Expand Down Expand Up @@ -200,3 +194,7 @@ def frictions(sliders):
plt.plot(xdes, ydes)
plt.plot(xx, yy)
plt.show()


if __name__ == "__main__":
main()
14 changes: 9 additions & 5 deletions examples/tools/pybullet_vehicle_example.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
import math
from pathlib import Path

from smarts.core.chassis import AckermannChassis
from smarts.bullet import pybullet
from smarts.bullet.chassis import BulletAckermannChassis
from smarts.bullet.pybullet import bullet_client as bc
from smarts.core.controllers.actuator_dynamic_controller import (
ActuatorDynamicController,
ActuatorDynamicControllerState,
)
from smarts.core.coordinates import Heading, Pose
from smarts.core.utils import pybullet
from smarts.core.utils.pybullet import bullet_client as bc
from smarts.core.vehicle import Vehicle

TIMESTEP_SEC = 1 / 240
Expand Down Expand Up @@ -90,7 +90,7 @@ def frictions(sliders, client):
)


if __name__ == "__main__":
def main():
# https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html
# mp.set_start_method('spawn', force=True)

Expand Down Expand Up @@ -136,7 +136,7 @@ def frictions(sliders, client):
pose = pose = Pose.from_center((0, 0, 0), Heading(0))
vehicle = Vehicle(
id="vehicle",
chassis=AckermannChassis(
chassis=BulletAckermannChassis(
pose=pose,
bullet_client=client,
),
Expand All @@ -149,3 +149,7 @@ def frictions(sliders, client):
sliders,
n_steps=int(1e6),
)


if __name__ == "__main__":
main()
21 changes: 21 additions & 0 deletions smarts/bullet/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
# MIT License
#
# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved.
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
# in the Software without restriction, including without limitation the rights
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
# copies of the Software, and to permit persons to whom the Software is
# furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT. IN NO EVENT SHALL THE
# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
# THE SOFTWARE.
4 changes: 2 additions & 2 deletions smarts/core/utils/bullet.py → smarts/bullet/bullet.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@

import numpy as np

from smarts.bullet import pybullet
from smarts.bullet.pybullet import bullet_client as bc
from smarts.core.coordinates import Pose
from smarts.core.utils import pybullet
from smarts.core.utils.pybullet import bullet_client as bc


class BulletClient:
Expand Down
Loading