├── .docs ├── gazebo_launch.png ├── gazebo_rviz_launch.png ├── gazebo_velodyne_launch.png ├── gazebo_velodyne_rviz_launch.png └── go2_teleop.mp4 ├── README.md ├── champ ├── .travis.yml ├── LICENSE ├── README.md ├── champ │ ├── CMakeLists.txt │ ├── include │ │ └── champ │ │ │ ├── LICENSE │ │ │ ├── README.md │ │ │ ├── bla │ │ │ ├── basic_linear_algebra.h │ │ │ └── memory_delegate.h │ │ │ ├── body_controller │ │ │ └── body_controller.h │ │ │ ├── geometry │ │ │ └── geometry.h │ │ │ ├── kinematics │ │ │ └── kinematics.h │ │ │ ├── leg_controller │ │ │ ├── leg_controller.h │ │ │ ├── phase_generator.h │ │ │ └── trajectory_planner.h │ │ │ ├── macros │ │ │ └── macros.h │ │ │ ├── odometry │ │ │ └── odometry.h │ │ │ ├── quadruped_base │ │ │ ├── quadruped_base.h │ │ │ ├── quadruped_components.h │ │ │ ├── quadruped_joint.h │ │ │ └── quadruped_leg.h │ │ │ └── utils │ │ │ ├── urdf_loader.h │ │ │ └── xmlrpc_helpers.h │ └── package.xml ├── champ_base │ ├── .gitignore │ ├── CMakeLists.txt │ ├── config │ │ ├── ekf │ │ │ ├── base_to_footprint.yaml │ │ │ └── footprint_to_odom.yaml │ │ └── velocity_smoother │ │ │ └── velocity_smoother.yaml │ ├── include │ │ ├── actuator.h │ │ ├── message_relay.h │ │ ├── quadruped_controller.h │ │ └── state_estimation.h │ ├── package.xml │ └── src │ │ ├── message_relay.cpp │ │ ├── message_relay_node.cpp │ │ ├── quadruped_controller.cpp │ │ ├── quadruped_controller_node.cpp │ │ ├── state_estimation.cpp │ │ └── state_estimation_node.cpp ├── champ_bringup │ ├── CMakeLists.txt │ ├── champ_bringup │ │ ├── __init__.py │ │ └── joint_calibrator_relay.py │ ├── launch │ │ ├── bringup.launch │ │ ├── bringup.launch.py │ │ ├── include │ │ │ ├── laser │ │ │ │ ├── d435.launch │ │ │ │ ├── hokuyo.launch │ │ │ │ ├── kinect.launch │ │ │ │ ├── lms1xx.launch │ │ │ │ ├── realsense.launch │ │ │ │ ├── rplidar.launch │ │ │ │ ├── sim.launch │ │ │ │ ├── sweep.launch │ │ │ │ ├── xv11.launch │ │ │ │ └── ydlidar.launch │ │ │ └── velocity_smoother.launch │ │ ├── joints_gui.launch │ │ └── joints_gui.launch.py │ └── package.xml ├── champ_config │ ├── CMakeLists.txt │ ├── config │ │ ├── autonomy │ │ │ ├── navigation.yaml │ │ │ └── slam.yaml │ │ ├── gait │ │ │ └── gait.yaml │ │ ├── joints │ │ │ └── joints.yaml │ │ └── links │ │ │ └── links.yaml │ ├── include │ │ ├── gait_config.h │ │ ├── hardware_config.h │ │ └── quadruped_description.h │ ├── launch │ │ ├── bringup.launch.py │ │ ├── gazebo.launch.py │ │ ├── navigate.launch.py │ │ └── slam.launch.py │ ├── maps │ │ ├── map.pgm │ │ ├── map.yaml │ │ ├── playground.pgm │ │ └── playground.yaml │ ├── package.xml │ ├── setup.bash │ └── worlds │ │ ├── default.world │ │ ├── outdoor.world │ │ └── playground.world ├── champ_description │ ├── CMakeLists.txt │ ├── launch │ │ ├── description.launch │ │ ├── description.launch.py │ │ └── view_urdf.launch │ ├── meshes │ │ ├── arm │ │ │ ├── base.stl │ │ │ ├── lower_arm.stl │ │ │ ├── upper_arm.stl │ │ │ ├── wrist1.stl │ │ │ └── wrist2.stl │ │ ├── asus_camera_simple.dae │ │ ├── base.stl │ │ ├── base_simple.stl │ │ ├── hip.stl │ │ ├── hokuyo_utm_30lx.dae │ │ ├── lower_leg.stl │ │ ├── lower_leg_simple.stl │ │ ├── upper_leg.stl │ │ └── upper_leg_simple.stl │ ├── package.xml │ ├── rviz │ │ └── urdf_viewer.rviz │ └── urdf │ │ ├── accessories.urdf.xacro │ │ ├── asus_camera.urdf.xacro │ │ ├── champ.urdf │ │ ├── champ.urdf.xacro │ │ ├── champ_arm.urdf │ │ ├── champ_velodyne.urdf │ │ ├── gen_urdf │ │ ├── hokuyo_utm30lx.urdf.xacro │ │ ├── leg.urdf.xacro │ │ └── properties.urdf.xacro ├── champ_gazebo │ ├── CMakeLists.txt │ ├── config │ │ ├── gazebo.yaml │ │ └── ros_control.yaml │ ├── launch │ │ ├── gazebo.launch │ │ ├── gazebo.launch.py │ │ ├── spawn_robot.launch │ │ └── spawn_world.launch │ ├── package.xml │ ├── scripts │ │ ├── imu_sensor.py │ │ ├── odometry.py │ │ └── odometry_tf.py │ ├── src │ │ └── contact_sensor.cpp │ └── worlds │ │ ├── default.world │ │ ├── outdoor.world │ │ └── playground.world ├── champ_msgs │ ├── CMakeLists.txt │ ├── msg │ │ ├── Contacts.msg │ │ ├── ContactsStamped.msg │ │ ├── Imu.msg │ │ ├── Joints.msg │ │ ├── PID.msg │ │ ├── Point.msg │ │ ├── PointArray.msg │ │ ├── Pose.msg │ │ └── Velocities.msg │ └── package.xml ├── champ_navigation │ ├── CMakeLists.txt │ ├── launch │ │ ├── navigate.launch.py │ │ └── slam.launch.py │ ├── package.xml │ └── rviz │ │ ├── navigation.rviz │ │ ├── navigation_minimal.rviz │ │ └── slam.rviz └── docs │ └── images │ ├── leg_stretched.png │ ├── navigation.gif │ ├── robots.gif │ └── slam.gif ├── champ_teleop ├── CMakeLists.txt ├── README.md ├── champ_teleop.py ├── launch │ └── teleop.launch.py └── package.xml └── robots ├── README.md ├── configs └── go2_config │ ├── CMakeLists.txt │ ├── config │ ├── autonomy │ │ ├── navigation.yaml │ │ └── slam.yaml │ ├── gait │ │ └── gait.yaml │ ├── joints │ │ └── joints.yaml │ ├── links │ │ └── links.yaml │ └── ros_control │ │ └── ros_control.yaml │ ├── include │ ├── gait_config.h │ ├── hardware_config.h │ └── quadruped_description.h │ ├── launch │ ├── bringup.launch.py │ ├── gazebo.launch.py │ ├── gazebo_velodyne.launch.py │ ├── navigate.launch.py │ └── slam.launch.py │ ├── maps │ ├── map.pgm │ ├── map.yaml │ ├── playground.pgm │ └── playground.yaml │ ├── package.xml │ ├── setup.bash │ └── worlds │ ├── default.world │ ├── outdoor.world │ └── playground.world ├── descriptions └── go2_description │ ├── CMakeLists.txt │ ├── config │ ├── _joint_names_go2_description.yaml │ ├── _robot_control.yaml │ └── ros_control │ │ └── ros_control.yaml │ ├── dae │ ├── base.dae │ ├── calf.dae │ ├── calf_mirror.dae │ ├── foot.dae │ ├── hip.dae │ ├── thigh.dae │ └── thigh_mirror.dae │ ├── launch │ └── description.launch.py │ ├── meshes │ ├── calf.dae │ ├── calf_mirror.dae │ ├── foot.dae │ ├── hip.dae │ ├── hokuyo.dae │ ├── thigh.dae │ ├── thigh_mirror.dae │ └── trunk.dae │ ├── package.xml │ ├── urdf │ ├── .history │ │ ├── go2_description_20230904144240.urdf │ │ ├── go2_description_20230904182446.urdf │ │ ├── go2_description_20230904193628.urdf │ │ ├── go2_description_20230904193644.urdf │ │ ├── go2_description_20230904193653.urdf │ │ ├── go2_description_20230904193705.urdf │ │ ├── go2_description_20230904193710.urdf │ │ ├── go2_description_20230904193711.urdf │ │ ├── go2_description_20230905112047.urdf │ │ ├── go2_description_20230905112143.urdf │ │ ├── go2_description_20230905112217.urdf │ │ ├── go2_description_20230905112735.urdf │ │ ├── go2_description_20230905112749.urdf │ │ ├── go2_description_20230905112752.urdf │ │ ├── go2_description_20230905112944.urdf │ │ ├── go2_description_20230905113000.urdf │ │ ├── go2_description_20230905113059.urdf │ │ ├── go2_description_20230905113633.urdf │ │ ├── go2_description_20230905113754.urdf │ │ ├── go2_description_20230905113755.urdf │ │ ├── go2_description_20230905113839.urdf │ │ ├── go2_description_20230905113840.urdf │ │ ├── go2_description_20230905114759.urdf │ │ ├── go2_description_20230905114819.urdf │ │ ├── go2_description_20230905115021.urdf │ │ ├── go2_description_20230905115022.urdf │ │ ├── go2_description_20230905115040.urdf │ │ ├── go2_description_20230905115215.urdf │ │ ├── go2_description_20230905115226.urdf │ │ ├── go2_description_20230905115300.urdf │ │ └── go2_description_20230905115313.urdf │ ├── Amended_collision_model.png │ ├── Normal_collision_model.png │ └── go2_description.urdf │ └── xacro │ ├── const.xacro │ ├── gazebo.xacro │ ├── laser.xacro │ ├── leg.xacro │ ├── materials.xacro │ ├── robot.xacro │ ├── robot_VLP.xacro │ ├── transmission.xacro │ └── velodyne.xacro ├── install_descriptions └── update_robots /.docs/gazebo_launch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/.docs/gazebo_launch.png -------------------------------------------------------------------------------- /.docs/gazebo_rviz_launch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/.docs/gazebo_rviz_launch.png -------------------------------------------------------------------------------- /.docs/gazebo_velodyne_launch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/.docs/gazebo_velodyne_launch.png -------------------------------------------------------------------------------- /.docs/gazebo_velodyne_rviz_launch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/.docs/gazebo_velodyne_rviz_launch.png -------------------------------------------------------------------------------- /.docs/go2_teleop.mp4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/.docs/go2_teleop.mp4 -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/README.md -------------------------------------------------------------------------------- /champ/.travis.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/.travis.yml -------------------------------------------------------------------------------- /champ/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/LICENSE -------------------------------------------------------------------------------- /champ/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/README.md -------------------------------------------------------------------------------- /champ/champ/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ/include/champ/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/LICENSE -------------------------------------------------------------------------------- /champ/champ/include/champ/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/README.md -------------------------------------------------------------------------------- /champ/champ/include/champ/bla/basic_linear_algebra.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/bla/basic_linear_algebra.h -------------------------------------------------------------------------------- /champ/champ/include/champ/bla/memory_delegate.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/bla/memory_delegate.h -------------------------------------------------------------------------------- /champ/champ/include/champ/body_controller/body_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/body_controller/body_controller.h -------------------------------------------------------------------------------- /champ/champ/include/champ/geometry/geometry.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/geometry/geometry.h -------------------------------------------------------------------------------- /champ/champ/include/champ/kinematics/kinematics.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/kinematics/kinematics.h -------------------------------------------------------------------------------- /champ/champ/include/champ/leg_controller/leg_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/leg_controller/leg_controller.h -------------------------------------------------------------------------------- /champ/champ/include/champ/leg_controller/phase_generator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/leg_controller/phase_generator.h -------------------------------------------------------------------------------- /champ/champ/include/champ/leg_controller/trajectory_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/leg_controller/trajectory_planner.h -------------------------------------------------------------------------------- /champ/champ/include/champ/macros/macros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/macros/macros.h -------------------------------------------------------------------------------- /champ/champ/include/champ/odometry/odometry.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/odometry/odometry.h -------------------------------------------------------------------------------- /champ/champ/include/champ/quadruped_base/quadruped_base.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/quadruped_base/quadruped_base.h -------------------------------------------------------------------------------- /champ/champ/include/champ/quadruped_base/quadruped_components.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/quadruped_base/quadruped_components.h -------------------------------------------------------------------------------- /champ/champ/include/champ/quadruped_base/quadruped_joint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/quadruped_base/quadruped_joint.h -------------------------------------------------------------------------------- /champ/champ/include/champ/quadruped_base/quadruped_leg.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/quadruped_base/quadruped_leg.h -------------------------------------------------------------------------------- /champ/champ/include/champ/utils/urdf_loader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/utils/urdf_loader.h -------------------------------------------------------------------------------- /champ/champ/include/champ/utils/xmlrpc_helpers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/include/champ/utils/xmlrpc_helpers.h -------------------------------------------------------------------------------- /champ/champ/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ/package.xml -------------------------------------------------------------------------------- /champ/champ_base/.gitignore: -------------------------------------------------------------------------------- 1 | include/libchamp -------------------------------------------------------------------------------- /champ/champ_base/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_base/config/ekf/base_to_footprint.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/config/ekf/base_to_footprint.yaml -------------------------------------------------------------------------------- /champ/champ_base/config/ekf/footprint_to_odom.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/config/ekf/footprint_to_odom.yaml -------------------------------------------------------------------------------- /champ/champ_base/config/velocity_smoother/velocity_smoother.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/config/velocity_smoother/velocity_smoother.yaml -------------------------------------------------------------------------------- /champ/champ_base/include/actuator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/include/actuator.h -------------------------------------------------------------------------------- /champ/champ_base/include/message_relay.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/include/message_relay.h -------------------------------------------------------------------------------- /champ/champ_base/include/quadruped_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/include/quadruped_controller.h -------------------------------------------------------------------------------- /champ/champ_base/include/state_estimation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/include/state_estimation.h -------------------------------------------------------------------------------- /champ/champ_base/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/package.xml -------------------------------------------------------------------------------- /champ/champ_base/src/message_relay.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/message_relay.cpp -------------------------------------------------------------------------------- /champ/champ_base/src/message_relay_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/message_relay_node.cpp -------------------------------------------------------------------------------- /champ/champ_base/src/quadruped_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/quadruped_controller.cpp -------------------------------------------------------------------------------- /champ/champ_base/src/quadruped_controller_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/quadruped_controller_node.cpp -------------------------------------------------------------------------------- /champ/champ_base/src/state_estimation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/state_estimation.cpp -------------------------------------------------------------------------------- /champ/champ_base/src/state_estimation_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_base/src/state_estimation_node.cpp -------------------------------------------------------------------------------- /champ/champ_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_bringup/champ_bringup/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /champ/champ_bringup/champ_bringup/joint_calibrator_relay.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/champ_bringup/joint_calibrator_relay.py -------------------------------------------------------------------------------- /champ/champ_bringup/launch/bringup.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/bringup.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/bringup.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/bringup.launch.py -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/d435.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/d435.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/hokuyo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/hokuyo.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/kinect.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/kinect.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/lms1xx.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/lms1xx.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/realsense.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/realsense.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/rplidar.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/rplidar.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/sim.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/sim.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/sweep.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/sweep.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/xv11.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/xv11.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/laser/ydlidar.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/laser/ydlidar.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/include/velocity_smoother.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/include/velocity_smoother.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/joints_gui.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/joints_gui.launch -------------------------------------------------------------------------------- /champ/champ_bringup/launch/joints_gui.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/launch/joints_gui.launch.py -------------------------------------------------------------------------------- /champ/champ_bringup/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_bringup/package.xml -------------------------------------------------------------------------------- /champ/champ_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_config/config/autonomy/navigation.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/config/autonomy/navigation.yaml -------------------------------------------------------------------------------- /champ/champ_config/config/autonomy/slam.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/config/autonomy/slam.yaml -------------------------------------------------------------------------------- /champ/champ_config/config/gait/gait.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/config/gait/gait.yaml -------------------------------------------------------------------------------- /champ/champ_config/config/joints/joints.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/config/joints/joints.yaml -------------------------------------------------------------------------------- /champ/champ_config/config/links/links.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/config/links/links.yaml -------------------------------------------------------------------------------- /champ/champ_config/include/gait_config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/include/gait_config.h -------------------------------------------------------------------------------- /champ/champ_config/include/hardware_config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/include/hardware_config.h -------------------------------------------------------------------------------- /champ/champ_config/include/quadruped_description.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/include/quadruped_description.h -------------------------------------------------------------------------------- /champ/champ_config/launch/bringup.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/launch/bringup.launch.py -------------------------------------------------------------------------------- /champ/champ_config/launch/gazebo.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/launch/gazebo.launch.py -------------------------------------------------------------------------------- /champ/champ_config/launch/navigate.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/launch/navigate.launch.py -------------------------------------------------------------------------------- /champ/champ_config/launch/slam.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/launch/slam.launch.py -------------------------------------------------------------------------------- /champ/champ_config/maps/map.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/maps/map.pgm -------------------------------------------------------------------------------- /champ/champ_config/maps/map.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/maps/map.yaml -------------------------------------------------------------------------------- /champ/champ_config/maps/playground.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/maps/playground.pgm -------------------------------------------------------------------------------- /champ/champ_config/maps/playground.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/maps/playground.yaml -------------------------------------------------------------------------------- /champ/champ_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/package.xml -------------------------------------------------------------------------------- /champ/champ_config/setup.bash: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/setup.bash -------------------------------------------------------------------------------- /champ/champ_config/worlds/default.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/worlds/default.world -------------------------------------------------------------------------------- /champ/champ_config/worlds/outdoor.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/worlds/outdoor.world -------------------------------------------------------------------------------- /champ/champ_config/worlds/playground.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_config/worlds/playground.world -------------------------------------------------------------------------------- /champ/champ_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_description/launch/description.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/launch/description.launch -------------------------------------------------------------------------------- /champ/champ_description/launch/description.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/launch/description.launch.py -------------------------------------------------------------------------------- /champ/champ_description/launch/view_urdf.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/launch/view_urdf.launch -------------------------------------------------------------------------------- /champ/champ_description/meshes/arm/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/arm/base.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/arm/lower_arm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/arm/lower_arm.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/arm/upper_arm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/arm/upper_arm.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/arm/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/arm/wrist1.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/arm/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/arm/wrist2.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/asus_camera_simple.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/asus_camera_simple.dae -------------------------------------------------------------------------------- /champ/champ_description/meshes/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/base.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/base_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/base_simple.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/hip.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/hip.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/hokuyo_utm_30lx.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/hokuyo_utm_30lx.dae -------------------------------------------------------------------------------- /champ/champ_description/meshes/lower_leg.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/lower_leg.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/lower_leg_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/lower_leg_simple.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/upper_leg.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/upper_leg.stl -------------------------------------------------------------------------------- /champ/champ_description/meshes/upper_leg_simple.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/meshes/upper_leg_simple.stl -------------------------------------------------------------------------------- /champ/champ_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/package.xml -------------------------------------------------------------------------------- /champ/champ_description/rviz/urdf_viewer.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/rviz/urdf_viewer.rviz -------------------------------------------------------------------------------- /champ/champ_description/urdf/accessories.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/accessories.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_description/urdf/asus_camera.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/asus_camera.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_description/urdf/champ.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/champ.urdf -------------------------------------------------------------------------------- /champ/champ_description/urdf/champ.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/champ.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_description/urdf/champ_arm.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/champ_arm.urdf -------------------------------------------------------------------------------- /champ/champ_description/urdf/champ_velodyne.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/champ_velodyne.urdf -------------------------------------------------------------------------------- /champ/champ_description/urdf/gen_urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/gen_urdf -------------------------------------------------------------------------------- /champ/champ_description/urdf/hokuyo_utm30lx.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/hokuyo_utm30lx.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_description/urdf/leg.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/leg.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_description/urdf/properties.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_description/urdf/properties.urdf.xacro -------------------------------------------------------------------------------- /champ/champ_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_gazebo/config/gazebo.yaml: -------------------------------------------------------------------------------- 1 | gazebo: 2 | ros__parameters: 3 | publish_rate: 200.0 -------------------------------------------------------------------------------- /champ/champ_gazebo/config/ros_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/config/ros_control.yaml -------------------------------------------------------------------------------- /champ/champ_gazebo/launch/gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/launch/gazebo.launch -------------------------------------------------------------------------------- /champ/champ_gazebo/launch/gazebo.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/launch/gazebo.launch.py -------------------------------------------------------------------------------- /champ/champ_gazebo/launch/spawn_robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/launch/spawn_robot.launch -------------------------------------------------------------------------------- /champ/champ_gazebo/launch/spawn_world.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/launch/spawn_world.launch -------------------------------------------------------------------------------- /champ/champ_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/package.xml -------------------------------------------------------------------------------- /champ/champ_gazebo/scripts/imu_sensor.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/scripts/imu_sensor.py -------------------------------------------------------------------------------- /champ/champ_gazebo/scripts/odometry.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/scripts/odometry.py -------------------------------------------------------------------------------- /champ/champ_gazebo/scripts/odometry_tf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/scripts/odometry_tf.py -------------------------------------------------------------------------------- /champ/champ_gazebo/src/contact_sensor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/src/contact_sensor.cpp -------------------------------------------------------------------------------- /champ/champ_gazebo/worlds/default.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/worlds/default.world -------------------------------------------------------------------------------- /champ/champ_gazebo/worlds/outdoor.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/worlds/outdoor.world -------------------------------------------------------------------------------- /champ/champ_gazebo/worlds/playground.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_gazebo/worlds/playground.world -------------------------------------------------------------------------------- /champ/champ_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Contacts.msg: -------------------------------------------------------------------------------- 1 | bool[] contacts -------------------------------------------------------------------------------- /champ/champ_msgs/msg/ContactsStamped.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/ContactsStamped.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Imu.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/Imu.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Joints.msg: -------------------------------------------------------------------------------- 1 | float32[] position -------------------------------------------------------------------------------- /champ/champ_msgs/msg/PID.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/PID.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Point.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/Point.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/PointArray.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/PointArray.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Pose.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/Pose.msg -------------------------------------------------------------------------------- /champ/champ_msgs/msg/Velocities.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/msg/Velocities.msg -------------------------------------------------------------------------------- /champ/champ_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_msgs/package.xml -------------------------------------------------------------------------------- /champ/champ_navigation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/CMakeLists.txt -------------------------------------------------------------------------------- /champ/champ_navigation/launch/navigate.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/launch/navigate.launch.py -------------------------------------------------------------------------------- /champ/champ_navigation/launch/slam.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/launch/slam.launch.py -------------------------------------------------------------------------------- /champ/champ_navigation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/package.xml -------------------------------------------------------------------------------- /champ/champ_navigation/rviz/navigation.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/rviz/navigation.rviz -------------------------------------------------------------------------------- /champ/champ_navigation/rviz/navigation_minimal.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/rviz/navigation_minimal.rviz -------------------------------------------------------------------------------- /champ/champ_navigation/rviz/slam.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/champ_navigation/rviz/slam.rviz -------------------------------------------------------------------------------- /champ/docs/images/leg_stretched.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/docs/images/leg_stretched.png -------------------------------------------------------------------------------- /champ/docs/images/navigation.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/docs/images/navigation.gif -------------------------------------------------------------------------------- /champ/docs/images/robots.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/docs/images/robots.gif -------------------------------------------------------------------------------- /champ/docs/images/slam.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ/docs/images/slam.gif -------------------------------------------------------------------------------- /champ_teleop/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ_teleop/CMakeLists.txt -------------------------------------------------------------------------------- /champ_teleop/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ_teleop/README.md -------------------------------------------------------------------------------- /champ_teleop/champ_teleop.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ_teleop/champ_teleop.py -------------------------------------------------------------------------------- /champ_teleop/launch/teleop.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ_teleop/launch/teleop.launch.py -------------------------------------------------------------------------------- /champ_teleop/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/champ_teleop/package.xml -------------------------------------------------------------------------------- /robots/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/README.md -------------------------------------------------------------------------------- /robots/configs/go2_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/CMakeLists.txt -------------------------------------------------------------------------------- /robots/configs/go2_config/config/autonomy/navigation.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/autonomy/navigation.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/config/autonomy/slam.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/autonomy/slam.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/config/gait/gait.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/gait/gait.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/config/joints/joints.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/joints/joints.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/config/links/links.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/links/links.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/config/ros_control/ros_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/config/ros_control/ros_control.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/include/gait_config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/include/gait_config.h -------------------------------------------------------------------------------- /robots/configs/go2_config/include/hardware_config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/include/hardware_config.h -------------------------------------------------------------------------------- /robots/configs/go2_config/include/quadruped_description.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/include/quadruped_description.h -------------------------------------------------------------------------------- /robots/configs/go2_config/launch/bringup.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/launch/bringup.launch.py -------------------------------------------------------------------------------- /robots/configs/go2_config/launch/gazebo.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/launch/gazebo.launch.py -------------------------------------------------------------------------------- /robots/configs/go2_config/launch/gazebo_velodyne.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/launch/gazebo_velodyne.launch.py -------------------------------------------------------------------------------- /robots/configs/go2_config/launch/navigate.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/launch/navigate.launch.py -------------------------------------------------------------------------------- /robots/configs/go2_config/launch/slam.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/launch/slam.launch.py -------------------------------------------------------------------------------- /robots/configs/go2_config/maps/map.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/maps/map.pgm -------------------------------------------------------------------------------- /robots/configs/go2_config/maps/map.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/maps/map.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/maps/playground.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/maps/playground.pgm -------------------------------------------------------------------------------- /robots/configs/go2_config/maps/playground.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/maps/playground.yaml -------------------------------------------------------------------------------- /robots/configs/go2_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/package.xml -------------------------------------------------------------------------------- /robots/configs/go2_config/setup.bash: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/setup.bash -------------------------------------------------------------------------------- /robots/configs/go2_config/worlds/default.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/worlds/default.world -------------------------------------------------------------------------------- /robots/configs/go2_config/worlds/outdoor.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/worlds/outdoor.world -------------------------------------------------------------------------------- /robots/configs/go2_config/worlds/playground.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/configs/go2_config/worlds/playground.world -------------------------------------------------------------------------------- /robots/descriptions/go2_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/CMakeLists.txt -------------------------------------------------------------------------------- /robots/descriptions/go2_description/config/_joint_names_go2_description.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/config/_joint_names_go2_description.yaml -------------------------------------------------------------------------------- /robots/descriptions/go2_description/config/_robot_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/config/_robot_control.yaml -------------------------------------------------------------------------------- /robots/descriptions/go2_description/config/ros_control/ros_control.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/config/ros_control/ros_control.yaml -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/base.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/calf.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/calf.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/calf_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/calf_mirror.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/foot.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/hip.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/hip.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/thigh.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/dae/thigh_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/dae/thigh_mirror.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/launch/description.launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/launch/description.launch.py -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/calf.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/calf.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/calf_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/calf_mirror.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/foot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/foot.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/hip.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/hip.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/hokuyo.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/hokuyo.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/thigh.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/thigh.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/thigh_mirror.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/thigh_mirror.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/meshes/trunk.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/meshes/trunk.dae -------------------------------------------------------------------------------- /robots/descriptions/go2_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/package.xml -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904144240.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904144240.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904182446.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904182446.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193628.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193628.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193644.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193644.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193653.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193653.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193705.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193705.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193710.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193710.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230904193711.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230904193711.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112047.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112047.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112143.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112143.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112217.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112217.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112735.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112735.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112749.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112749.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112752.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112752.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905112944.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905112944.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113000.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113000.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113059.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113059.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113633.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113633.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113754.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113754.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113755.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113755.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113839.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113839.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905113840.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905113840.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905114759.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905114759.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905114819.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905114819.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115021.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115021.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115022.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115022.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115040.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115040.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115215.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115215.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115226.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115226.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115300.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115300.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/.history/go2_description_20230905115313.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/.history/go2_description_20230905115313.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/Amended_collision_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/Amended_collision_model.png -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/Normal_collision_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/Normal_collision_model.png -------------------------------------------------------------------------------- /robots/descriptions/go2_description/urdf/go2_description.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/urdf/go2_description.urdf -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/const.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/const.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/gazebo.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/laser.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/laser.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/leg.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/leg.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/materials.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/materials.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/robot.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/robot.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/robot_VLP.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/robot_VLP.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/transmission.xacro -------------------------------------------------------------------------------- /robots/descriptions/go2_description/xacro/velodyne.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/descriptions/go2_description/xacro/velodyne.xacro -------------------------------------------------------------------------------- /robots/install_descriptions: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/install_descriptions -------------------------------------------------------------------------------- /robots/update_robots: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/anujjain-dev/unitree-go2-ros2/HEAD/robots/update_robots --------------------------------------------------------------------------------