#include <orientation_controller.h>
|
bool | getTransform (const ros::Time &time, geometry_msgs::TransformStamped &source2target, const double x, const double y, const double z, const double w) |
|
void | imuDataCallback (const sensor_msgs::Imu::ConstPtr &msg) |
|
|
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
|
enum | ControllerState {
ControllerState::CONSTRUCTED,
ControllerState::INITIALIZED,
ControllerState::RUNNING,
ControllerState::STOPPED,
ControllerState::WAITING,
ControllerState::ABORTED
} |
|
ControllerState | state_ |
|
bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
|
static void | clearClaims (hardware_interface::RobotHW *robot_hw) |
|
static void | extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out) |
|
static bool | hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw) |
|
static void | populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources) |
|
bool | allow_optional_interfaces_ |
|
hardware_interface::RobotHW | robot_hw_ctrl_ |
|
Definition at line 16 of file orientation_controller.h.
◆ Controller()
rm_orientation_controller::Controller::Controller |
( |
| ) |
|
|
default |
◆ getTransform()
bool Controller::getTransform |
( |
const ros::Time & |
time, |
|
|
geometry_msgs::TransformStamped & |
source2target, |
|
|
const double |
x, |
|
|
const double |
y, |
|
|
const double |
z, |
|
|
const double |
w |
|
) |
| |
|
private |
◆ imuDataCallback()
void Controller::imuDataCallback |
( |
const sensor_msgs::Imu::ConstPtr & |
msg | ) |
|
|
private |
◆ init()
◆ update()
◆ frame_source_
std::string rm_orientation_controller::Controller::frame_source_ |
|
private |
◆ frame_target_
std::string rm_orientation_controller::Controller::frame_target_ |
|
private |
◆ imu_data_sub_
◆ imu_sensor_
◆ last_imu_update_time_
ros::Time rm_orientation_controller::Controller::last_imu_update_time_ |
|
private |
◆ receive_imu_msg_
bool rm_orientation_controller::Controller::receive_imu_msg_ = false |
|
private |
◆ robot_state_
◆ source2target_msg_
geometry_msgs::TransformStamped rm_orientation_controller::Controller::source2target_msg_ |
|
private |
◆ tf_broadcaster_
The documentation for this class was generated from the following files: