Skip to content

Commit

Permalink
Updates for Isaac Sim 4.0.0
Browse files Browse the repository at this point in the history
  • Loading branch information
ayushgnv committed Jun 4, 2024
1 parent 2ef4d93 commit d686d15
Show file tree
Hide file tree
Showing 83 changed files with 1,507 additions and 1,017 deletions.
15 changes: 15 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# Changelog

## [1.0.0] - 2024-05-28

### Added
- Ackermann publisher script for Ackermann Steering tutorial [Noetic, Foxy, Humble]
- New `isaacsim` package to enable running Isaac Sim as a ROS2 node or from a ROS2 launch file! [Foxy, Humble]
- `isaac_ros2_messages` service interfaces for listing prims and manipulate their attributes [Foxy, Humble]

### Removed
- Removed support for quadruped VINS Fusion example [Noetic]

## [0.1.0] - 2023-12-18
### Added
- Noetic, Foxy, Humble workspaces for Isaac Sim 2023.1.1
2 changes: 1 addition & 1 deletion foxy_ws/fastdds.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8" ?>

<license>Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
<license>Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.
NVIDIA CORPORATION and its licensors retain all intellectual property
and proprietary rights in and to this software, related documentation
and any modifications thereto. Any use, reproduction, disclosure or
Expand Down
13 changes: 11 additions & 2 deletions foxy_ws/src/custom_message/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,17 @@
<name>custom_message</name>
<version>0.0.0</version>
<description>Custom Message Sample Package</description>
<maintainer email="[email protected]">isaac sim</maintainer>
<license>TODO: License declaration</license>
<maintainer email="[email protected]">Isaac Sim</maintainer>

<license>Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.
NVIDIA CORPORATION and its licensors retain all intellectual property
and proprietary rights in and to this software, related documentation
and any modifications thereto. Any use, reproduction, disclosure or
distribution of this software and related documentation without an express
license agreement from NVIDIA CORPORATION is strictly prohibited.</license>

<url type="Documentation">https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html</url>
<url type="Forums">https://forums.developer.nvidia.com/c/omniverse/simulation/69</url>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand Down
8 changes: 6 additions & 2 deletions foxy_ws/src/isaac_ros2_messages/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,11 @@ find_package(geometry_msgs REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"srv/IsaacPose.srv"
"srv/GetPrims.srv"
"srv/GetPrimAttributes.srv"
"srv/GetPrimAttribute.srv"
"srv/SetPrimAttribute.srv"
DEPENDENCIES builtin_interfaces std_msgs geometry_msgs
)
)

ament_package()
ament_package()
8 changes: 4 additions & 4 deletions foxy_ws/src/isaac_ros2_messages/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,19 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>isaac_ros2_messages</name>
<version>0.1.0</version>
<version>0.2.0</version>
<description>ROS2 messages for isaac ros2 bridge</description>
<maintainer email="isaac-sim@todo.todo">isaac sim</maintainer>
<maintainer email="isaac-sim[email protected]">Isaac Sim</maintainer>

<license>Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
<license>Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.
NVIDIA CORPORATION and its licensors retain all intellectual property
and proprietary rights in and to this software, related documentation
and any modifications thereto. Any use, reproduction, disclosure or
distribution of this software and related documentation without an express
license agreement from NVIDIA CORPORATION is strictly prohibited.</license>

<url type="Documentation">https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html</url>
<url type="Forums">https://forums.developer.nvidia.com/c/agx-autonomous-machines/isaac/simulation</url>
<url type="Forums">https://forums.developer.nvidia.com/c/omniverse/simulation/69</url>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand Down
7 changes: 7 additions & 0 deletions foxy_ws/src/isaac_ros2_messages/srv/GetPrimAttribute.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
string path # prim path
string attribute # attribute name
---
string value # attribute value (as JSON)
string type # attribute type
bool success # indicate a successful execution of the service
string message # informational, e.g. for error messages
7 changes: 7 additions & 0 deletions foxy_ws/src/isaac_ros2_messages/srv/GetPrimAttributes.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
string path # prim path
---
string[] names # list of attribute base names (name used to Get or Set an attribute)
string[] displays # list of attribute display names (name displayed in Property tab)
string[] types # list of attribute data types
bool success # indicate a successful execution of the service
string message # informational, e.g. for error messages
6 changes: 6 additions & 0 deletions foxy_ws/src/isaac_ros2_messages/srv/GetPrims.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
string path # get prims at path
---
string[] paths # list of prim paths
string[] types # prim type names
bool success # indicate a successful execution of the service
string message # informational, e.g. for error messages
6 changes: 6 additions & 0 deletions foxy_ws/src/isaac_ros2_messages/srv/SetPrimAttribute.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
string path # prim path
string attribute # attribute name
string value # attribute value (as JSON)
---
bool success # indicate a successful execution of the service
string message # informational, e.g. for error messages
1 change: 1 addition & 0 deletions foxy_ws/src/isaac_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ install(DIRECTORY
# Install Python executables
install(PROGRAMS
scripts/ros2_publisher.py
scripts/ros2_ackermann_publisher.py
DESTINATION lib/${PROJECT_NAME}
)
ament_package()
7 changes: 4 additions & 3 deletions foxy_ws/src/isaac_tutorials/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,24 +7,25 @@
The isaac_tutorials package
</description>

<maintainer email="isaac-sim@todo.todo">isaac sim</maintainer>
<maintainer email="isaac-sim[email protected]">Isaac Sim</maintainer>

<license>Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
<license>Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.
NVIDIA CORPORATION and its licensors retain all intellectual property
and proprietary rights in and to this software, related documentation
and any modifications thereto. Any use, reproduction, disclosure or
distribution of this software and related documentation without an express
license agreement from NVIDIA CORPORATION is strictly prohibited.</license>

<url type="Documentation">https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html</url>
<url type="Forums">https://forums.developer.nvidia.com/c/agx-autonomous-machines/isaac/simulation</url>
<url type="Forums">https://forums.developer.nvidia.com/c/omniverse/simulation/69</url>

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>launch</build_depend>
<build_depend>launch_ros</build_depend>

<build_depend>joint_state_publisher</build_depend>
<build_depend>ackermann_msgs</build_depend>

<build_depend>rviz2</build_depend>
<build_depend>turtlebot3</build_depend>
Expand Down
42 changes: 21 additions & 21 deletions foxy_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -57,17 +57,17 @@ Visualization Manager:
Value: true
front_3d_lidar:
Value: true
front_stereo_camera:imu:
front_stereo_camera_imu:
Value: true
front_stereo_camera:left_rgb:
front_stereo_camera_left_optical:
Value: true
front_stereo_camera:right_rgb:
front_stereo_camera_right_optical:
Value: true
left_stereo_camera:imu:
left_stereo_camera_imu:
Value: true
left_stereo_camera:left_rgb:
left_stereo_camera_left_optical:
Value: true
left_stereo_camera:right_rgb:
left_stereo_camera_right_optical:
Value: true
odom:
Value: true
Expand All @@ -79,11 +79,11 @@ Visualization Manager:
Value: true
rear_stereo_camera:right_rgb:
Value: true
right_stereo_camera:imu:
right_stereo_camera_imu:
Value: true
right_stereo_camera:left_rgb:
right_stereo_camera_left_optical:
Value: true
right_stereo_camera:right_rgb:
right_stereo_camera_right_optical:
Value: true
Marker Scale: 1
Name: TF
Expand All @@ -99,17 +99,17 @@ Visualization Manager:
{}
front_3d_lidar:
{}
front_stereo_camera:imu:
front_stereo_camera_imu:
{}
front_stereo_camera:left_rgb:
front_stereo_camera_left_optical:
{}
front_stereo_camera:right_rgb:
front_stereo_camera_right_optical:
{}
left_stereo_camera:imu:
left_stereo_camera_imu:
{}
left_stereo_camera:left_rgb:
left_stereo_camera_left_optical:
{}
left_stereo_camera:right_rgb:
left_stereo_camera_right_optical:
{}
rear_2d_lidar:
{}
Expand All @@ -119,11 +119,11 @@ Visualization Manager:
{}
rear_stereo_camera:right_rgb:
{}
right_stereo_camera:imu:
right_stereo_camera_imu:
{}
right_stereo_camera:left_rgb:
right_stereo_camera_left_optical:
{}
right_stereo_camera:right_rgb:
right_stereo_camera_right_optical:
{}
Update Interval: 0
Value: true
Expand Down Expand Up @@ -177,7 +177,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /front_stereo_camera/left_rgb/image_raw
Value: /front_stereo_camera/left/image_raw
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Expand All @@ -191,7 +191,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /front_stereo_camera/right_rgb/image_raw
Value: /front_stereo_camera/right/image_raw
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Expand Down Expand Up @@ -222,7 +222,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /front_3d_lidar/point_cloud
Value: /front_3d_lidar/lidar_points
Use Fixed Frame: true
Use rainbow: true
Value: true
Expand Down
56 changes: 56 additions & 0 deletions foxy_ws/src/isaac_tutorials/scripts/ros2_ackermann_publisher.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#!/usr/bin/env python3

# Copyright (c) 2020-2024, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.

import rclpy
from rclpy.node import Node

from ackermann_msgs.msg import AckermannDriveStamped
import numpy as np

class MinimalPublisher(Node):

def __init__(self):
super().__init__('test_ackermann')
self.publisher_ = self.create_publisher(AckermannDriveStamped, 'ackermann_cmd', 10)
timer_period = 0.05 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0

def timer_callback(self):
msg = AckermannDriveStamped()

# Only command forklift using acceleration and steering angle
degrees1 = np.arange(0, 60)
degrees2 = np.arange(-60, 0)
degrees = np.concatenate((degrees1, degrees1[::-1], degrees2[::-1], degrees2))
msg.header.frame_id = "forklift"
msg.header.stamp = self.get_clock().now().to_msg()
msg.drive.steering_angle = 0.0174533 * (degrees[self.i % degrees.size])

msg.drive.acceleration = float(degrees[self.i % degrees.size])

self.publisher_.publish(msg)
self.i += 1


def main(args=None):

rclpy.init(args=args)

minimal_publisher = MinimalPublisher()

rclpy.spin(minimal_publisher)

minimal_publisher.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
18 changes: 18 additions & 0 deletions foxy_ws/src/isaacsim/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
cmake_minimum_required(VERSION 3.5)
project(isaacsim)

find_package(ament_cmake REQUIRED)
find_package(rclpy REQUIRED)

install(DIRECTORY
scripts
launch
DESTINATION share/${PROJECT_NAME})

# Install Python executables
install(PROGRAMS
scripts/run_isaacsim.py
scripts/open_isaacsim_stage.py
DESTINATION lib/${PROJECT_NAME}
)
ament_package()
Loading

0 comments on commit d686d15

Please sign in to comment.