Skip to content
Open
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
1 change: 0 additions & 1 deletion keyboard_controls/keyboard_controls.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
from rclpy.node import Node
from tr_messages.msg import SimTeleopInput
from pynput import keyboard
import numpy
from sim_node import constants


Expand Down
12 changes: 7 additions & 5 deletions sim_node/comp_field.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,16 @@
import os
from sim_node import infantry_robot
import numpy as np
from sim_node import infantry_robot
from mani_skill.agents.multi_agent import MultiAgent
from mani_skill.sensors.camera import *
from mani_skill.sensors.camera import (
parse_camera_configs,
update_camera_configs_from_dict,
CameraConfig,
)
from mani_skill.sensors.depth_camera import StereoDepthCameraConfig, StereoDepthCamera
from mani_skill.sensors.camera import Camera
from mani_skill.utils.structs.render_camera import RenderCamera
from mani_skill.utils.structs.pose import Pose
# from mani_skill.utils.structs.pose import Pose

package_dir = get_package_share_directory("sim_node")
base_field_path = "resource/models/field/"
Expand Down Expand Up @@ -42,7 +45,6 @@

@register_env("comp_field")
class CompFieldEnv(BaseEnv):

def __init__(self, *args, robot_uids=("infantry"), **kwargs):
super().__init__(*args, robot_uids=robot_uids, **kwargs)

Expand Down Expand Up @@ -80,7 +82,7 @@ def _load_agent(self, options: dict):
def _step_action(
self, action: None | np.ndarray | infantry_robot.Tensor | Dict
) -> None | infantry_robot.Tensor:
plate_poses = self.agent.agents[0].get_armor_panel_poses()
# plate_poses = self.agent.agents[0].get_armor_panel_poses()

# cube = self.scene.actors["debug_cube"]
# cube.set_pose(plate_poses[3])
Expand Down
11 changes: 6 additions & 5 deletions sim_node/infantry_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,11 @@
import sapien
import numpy as np
from mani_skill.agents.base_agent import BaseAgent, Keyframe
from mani_skill.agents.controllers import *
from mani_skill.agents.controllers import (
deepcopy_dict,
PDJointPosControllerConfig,
PDBaseVelControllerConfig,
)
from mani_skill.agents.registration import register_agent
from mani_skill.sensors.camera import CameraConfig
from torch import Tensor
Expand All @@ -19,9 +23,7 @@
@register_agent()
class InfantryRobot(BaseAgent):
uid = "infantry"
urdf_path = str(
os.path.join(package_dir, "resource/models/infantry/infantry.urdf")
)
urdf_path = str(os.path.join(package_dir, "resource/models/infantry/infantry.urdf"))

# TODO ideally we define a srdf file instead of disabling all collisions. That way we only disable problematic collisions and
disable_self_collisions = True
Expand Down Expand Up @@ -88,7 +90,6 @@ def _after_loading_articulation(self):

@property
def _controller_configs(self):

pitch_pd_joint = PDJointPosControllerConfig(
self.pitch_joint_names,
lower=None,
Expand Down
5 changes: 0 additions & 5 deletions sim_node/ros_bridge.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,17 +3,13 @@
from rclpy.node import Node
from tr_messages.srv import WriteSerial, ListenSerial
from tr_messages.msg import SimTeleopInput, RobotGroundTruth, SimGroundTruth
from sensor_msgs.msg import Image
from sim_node import simulation

from sensor_msgs.msg import Image, PointCloud2, PointField
from std_msgs.msg import Header
from sensor_msgs_py import point_cloud2 # pointcloud utilizes
from rosgraph_msgs.msg import Clock
from tf2_msgs.msg import TFMessage
from geometry_msgs.msg import TransformStamped
from sim_node import utils, constants
import numpy as np

from cv_bridge import CvBridge
import torch
Expand Down Expand Up @@ -294,7 +290,6 @@ def secondary_robot_teleop_callback(self, msg):
)

def points_to_ros_pointcloud2(self, points):

header = Header()
# TODO FIX ME
header.stamp = self.get_clock().now().to_msg()
Expand Down
7 changes: 1 addition & 6 deletions sim_node/simulation.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,5 @@
import gymnasium as gym
import mani_skill.envs
from mani_skill.envs.sapien_env import BaseEnv
from mani_skill.agents.base_agent import BaseAgent
from mani_skill.agents.multi_agent import MultiAgent
from sim_node import comp_field
import numpy as np
from sim_node import utils
from mani_skill.utils.structs import SimConfig
Expand All @@ -21,7 +17,6 @@


class Simulation:

def __init__(self, options: dict, seed=2930):
self.options = dict(reconfigure=True, user=options)
self.should_render_gui = self.options["user"]["human_gui"]
Expand Down Expand Up @@ -99,7 +94,7 @@ def step(
}

obs, reward, terminated, truncated, info = self.env.step(action=action)
done = terminated or truncated
# done = terminated or truncated
if self.should_render_gui:
self.env.render()

Expand Down
7 changes: 1 addition & 6 deletions sim_node/utils.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,9 @@
from typing import Dict

import numpy as np
import sapien.physx as physx
import torch

from mani_skill.sensors.base_sensor import BaseSensor, BaseSensorConfig
from mani_skill.sensors.camera import Camera
from mani_skill.utils import common

from tr_messages.msg import RobotGroundTruth, SimGroundTruth
from tr_messages.msg import RobotGroundTruth
from geometry_msgs.msg import Pose


Expand Down