ros2_control - humble
Loading...
Searching...
No Matches
Classes | Enumerations | Functions
mujoco_ros2_control Namespace Reference

Classes

struct  CameraData
 
struct  FTSensorData
 
class  HeadlessAdapter
 
struct  IMUSensorData
 
struct  InterfaceData
 
struct  LidarData
 
struct  MuJoCoActuatorData
 
class  MujocoCameras
 Wraps MuJoCo cameras for publishing ROS 2 RGB-D streams. More...
 
class  MujocoLidar
 Wraps MuJoCo rangefinder sensors for publishing ROS 2 LaserScan messages. More...
 
class  MujocoSystemInterface
 
class  ROS2ControlGlfwAdapter
 
struct  SensorData
 
struct  URDFJointData
 

Enumerations

enum class  ActuatorType {
  UNKNOWN , MOTOR , POSITION , VELOCITY ,
  PASSIVE , CUSTOM
}
 

Functions

std::optional< hardware_interface::ComponentInfoget_sensor_from_info (const hardware_interface::HardwareInfo &hardware_info, const std::string &name)
 Returns the sensor's component info for the provided sensor name, if it exists.
 
std::pair< std::string, int > parse_lidar_name (const std::string &sensor_name)
 
std::optional< LidarDataget_lidar_data (const hardware_interface::HardwareInfo &hardware_info, const std::string &name)
 
template<typename T >
void add_items (std::vector< T > &vector, const std::vector< T > &items)
 
double clamp (double v, double lo, double hi)
 
std::string getExecutableDir ()
 
void scanPluginLibraries ()
 
const char * Diverged (int disableflags, const mjData *d)
 
mjModel * loadModelFromFile (const char *file, mj::Simulate &sim)
 
mjModel * loadModelFromTopic (rclcpp::Node::SharedPtr node, const std::string &topic_name)
 
mjModel * LoadModel (const char *file, const std::string &topic, mj::Simulate &sim, rclcpp::Node::SharedPtr node)
 
ActuatorType getActuatorType (const mjModel *mj_model, int mujoco_actuator_id)
 
int get_actuator_id (const std::string &actuator_name, const mjModel *mj_model)
 Get the MuJoCo actuator ID based on a name. First this method looks for a joint that matches the passed name, and finds the actuator attached to it. If this doesn't exist, it will then look for the actuator with the passed name.
 
std::string get_joint_actuator_name (const std::string &joint_name, const hardware_interface::HardwareInfo &hardware_info, const mjModel *mj_model)
 Get the corresponding actuator name for a given joint name using transmissions.
 
std::vector< std::string > get_interfaces_in_order (const std::vector< std::string > &available_interfaces, const std::vector< std::string > &desired_order)
 Orders available interfaces based on a desired order.
 

Detailed Description

Copyright (c) 2025, United States Government, as represented by the Administrator of the National Aeronautics and Space Administration.

All rights reserved.

This software is licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Enumeration Type Documentation

◆ ActuatorType

Maps to MuJoCo actuator types:

  • MOTOR for MuJoCo motor actuator
  • POSITION for MuJoCo position actuator
  • VELOCITY for MuJoCo velocity actuator
  • CUSTOM for MuJoCo general actuator or other types
Note
the MuJoCo types are as per the MuJoCo documentation: https://mujoco.readthedocs.io/en/latest/XMLreference.html#actuator

Function Documentation

◆ get_actuator_id()

int mujoco_ros2_control::get_actuator_id ( const std::string &  actuator_name,
const mjModel *  mj_model 
)

Get the MuJoCo actuator ID based on a name. First this method looks for a joint that matches the passed name, and finds the actuator attached to it. If this doesn't exist, it will then look for the actuator with the passed name.

Parameters
actuator_nameThe name of the actuator.
mj_modelPointer to the MuJoCo model.
Returns
The actuator ID if found, otherwise -1.

◆ get_interfaces_in_order()

std::vector< std::string > mujoco_ros2_control::get_interfaces_in_order ( const std::vector< std::string > &  available_interfaces,
const std::vector< std::string > &  desired_order 
)

Orders available interfaces based on a desired order.

This function takes a list of available interfaces and a desired order, returning a new list where the interfaces are arranged according to the desired order. Any interfaces not specified in the desired order are appended at the end in their original order.

Parameters
available_interfacesA vector of available interface names.
desired_orderA vector specifying the desired order of interface names.
Returns
A vector of interface names ordered according to the desired order.

◆ get_joint_actuator_name()

std::string mujoco_ros2_control::get_joint_actuator_name ( const std::string &  joint_name,
const hardware_interface::HardwareInfo hardware_info,
const mjModel *  mj_model 
)

Get the corresponding actuator name for a given joint name using transmissions.

Parameters
joint_nameThe name of the joint.
hardware_infoThe hardware information containing transmissions.
mj_modelPointer to the MuJoCo model.
Returns
The corresponding actuator name if found, otherwise returns the joint name.

◆ get_lidar_data()

std::optional< LidarData > mujoco_ros2_control::get_lidar_data ( const hardware_interface::HardwareInfo hardware_info,
const std::string &  name 
)

Construct a LidarData object given a string sensor name and hardware_info object to parse.

◆ parse_lidar_name()

std::pair< std::string, int > mujoco_ros2_control::parse_lidar_name ( const std::string &  sensor_name)

Given a sensor in the form <sensor_name>-id, returns the name and id if possible. Otherwise, return "" and -1 to indicate failure.