#include <RelativePoseEstimatorNode.h>
|
| void | LoadRelativePoses (ros::NodeHandle &nodeHandle) |
| |
| void | PrepareMarkers (visualization_msgs::Marker &input, const char *ns, const int &id, const int &seq) |
| |
| void | SetNear (visualization_msgs::Marker &input) |
| |
| void | SetFar (visualization_msgs::Marker &input) |
| |
| void | CommCallback (std_msgs::Int8MultiArray::ConstPtr msg) |
| |
| void | Update () |
| |
◆ RelativePoseEstimatorNode()
| RelativePoseEstimatorNode::RelativePoseEstimatorNode |
( |
| ) |
|
◆ ~RelativePoseEstimatorNode()
| RelativePoseEstimatorNode::~RelativePoseEstimatorNode |
( |
| ) |
|
◆ CommCallback()
| void RelativePoseEstimatorNode::CommCallback |
( |
std_msgs::Int8MultiArray::ConstPtr |
msg | ) |
|
|
private |
◆ LoadRelativePoses()
| void RelativePoseEstimatorNode::LoadRelativePoses |
( |
ros::NodeHandle & |
nodeHandle | ) |
|
|
private |
◆ PrepareMarkers()
| void RelativePoseEstimatorNode::PrepareMarkers |
( |
visualization_msgs::Marker & |
input, |
|
|
const char * |
ns, |
|
|
const int & |
id, |
|
|
const int & |
seq |
|
) |
| |
|
private |
◆ SetFar()
| void RelativePoseEstimatorNode::SetFar |
( |
visualization_msgs::Marker & |
input | ) |
|
|
private |
◆ SetNear()
| void RelativePoseEstimatorNode::SetNear |
( |
visualization_msgs::Marker & |
input | ) |
|
|
private |
◆ Update()
| void RelativePoseEstimatorNode::Update |
( |
| ) |
|
|
private |
◆ aClusterMarkerFarMsg
| visualization_msgs::Marker RelativePoseEstimatorNode::aClusterMarkerFarMsg |
|
private |
◆ aClusterMarkerMsg
| visualization_msgs::Marker RelativePoseEstimatorNode::aClusterMarkerMsg |
|
private |
◆ aDistancesPublisher
| ros::Publisher RelativePoseEstimatorNode::aDistancesPublisher |
|
private |
◆ aFarMarkerPublisher
| ros::Publisher RelativePoseEstimatorNode::aFarMarkerPublisher |
|
private |
◆ aId
| int RelativePoseEstimatorNode::aId |
|
private |
◆ aNamespace
| std::string RelativePoseEstimatorNode::aNamespace |
|
private |
◆ aNearMarkerPublisher
| ros::Publisher RelativePoseEstimatorNode::aNearMarkerPublisher |
|
private |
◆ aQueueSize
| int RelativePoseEstimatorNode::aQueueSize |
|
private |
◆ aRate
| double RelativePoseEstimatorNode::aRate |
|
private |
◆ aReceivedPoses
| std::vector<bool> RelativePoseEstimatorNode::aReceivedPoses |
|
private |
◆ aRelativePoses
| std::vector<tf::Vector3> RelativePoseEstimatorNode::aRelativePoses |
|
private |
◆ aRelativePosesPublisher
| ros::Publisher RelativePoseEstimatorNode::aRelativePosesPublisher |
|
private |
◆ aRobots
| int RelativePoseEstimatorNode::aRobots |
|
private |
◆ aRobotsInCommMsg
| std_msgs::Int8MultiArray RelativePoseEstimatorNode::aRobotsInCommMsg |
|
private |
◆ aRobotsRelativeDistancesMsg
| std_msgs::Float64MultiArray RelativePoseEstimatorNode::aRobotsRelativeDistancesMsg |
|
private |
◆ aRobotsRelativePosesMsg
| geometry_msgs::PoseArray RelativePoseEstimatorNode::aRobotsRelativePosesMsg |
|
private |
◆ aRobotsRelStartingPosMsg
| geometry_msgs::PoseArray RelativePoseEstimatorNode::aRobotsRelStartingPosMsg |
|
private |
◆ aRobotsWorldPoses
| std::vector<geometry_msgs::Pose> RelativePoseEstimatorNode::aRobotsWorldPoses |
|
private |
◆ aSeq
| int RelativePoseEstimatorNode::aSeq |
|
private |
◆ aStartRelativePosesPublisher
| ros::Publisher RelativePoseEstimatorNode::aStartRelativePosesPublisher |
|
private |
◆ aSubscribers
| std::vector<ros::Subscriber> RelativePoseEstimatorNode::aSubscribers |
|
private |
◆ aTimers
| std::vector<ros::Timer> RelativePoseEstimatorNode::aTimers |
|
private |
The documentation for this class was generated from the following file: