Publishes contact states from gazebo.
More...
#include <contact_state_publisher.h>
|
void | contactStateCallback (const gazebo_msgs::ContactsState::ConstPtr &msg, const int toe_idx) |
| Processes new contact state data.
|
|
void | publishContactState () |
| Publishes current contact state data.
|
|
|
ros::Subscriber | toe0_contact_state_sub |
| Subscriber for toe 0.
|
|
ros::Subscriber | toe1_contact_state_sub |
| Subscriber for toe 1.
|
|
ros::Subscriber | toe2_contact_state_sub |
| Subscriber for toe 2.
|
|
ros::Subscriber | toe3_contact_state_sub |
| Subscriber for toe 3.
|
|
tf2_ros::Buffer | buffer_ |
| Tf2 buffer.
|
|
tf2_ros::TransformListener | listener_ |
| TF transform listener.
|
|
ros::Publisher | grf_pub_ |
| ROS publisher for desired GRF.
|
|
ros::NodeHandle | nh_ |
| Nodehandle to pub to and sub from.
|
|
double | update_rate_ |
| Update rate for sending and receiving data;.
|
|
const int | num_feet_ = 4 |
| Number of feet.
|
|
quad_msgs::GRFArray | grf_array_msg_ |
| Most recent local plan.
|
|
bool | ready_to_publish_ |
| Publish ready indicator.
|
|
Publishes contact states from gazebo.
This class subscribes to Gazebo contact state messages and publishes their data under one GRFArray message.
◆ ContactStatePublisher()
ContactStatePublisher::ContactStatePublisher |
( |
ros::NodeHandle |
nh | ) |
|
◆ contactStateCallback()
void ContactStatePublisher::contactStateCallback |
( |
const gazebo_msgs::ContactsState::ConstPtr & |
msg, |
|
|
const int |
toe_idx |
|
) |
| |
|
private |
Processes new contact state data.
- Parameters
-
[in] | msg | New contact state data |
The documentation for this class was generated from the following files:
- quad_simulator/gazebo_scripts/include/contact_state_publisher.h
- quad_simulator/gazebo_scripts/src/contact_state_publisher.cpp