#include <ros/ros.h>
#include <std_msgs/ColorRGBA.h>
#include <boost/format.hpp>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include "articulation_models/utils.h"
Go to the source code of this file.
Defines |
#define | VEC(p1) |
Functions |
double | getBIC (double loglh, size_t k, size_t n) |
std_msgs::ColorRGBA | HSV_to_RGB (double h, double s, double v) |
void | MAT_to_RPY (const tf::Matrix3x3 &mat, double &roll, double &pitch, double &yaw) |
std::string | pose_to_string (const geometry_msgs::Pose &pose) |
tf::Matrix3x3 | RPY_to_MAT (double roll, double pitch, double yaw) |
std::string | transform_to_string (const tf::Transform &p) |
std::string | uncert_to_string (double sigma_position, double sigma_orientation) |
Define Documentation
Value:"["<< \
p1.getOrigin().x() << "," << p1.getOrigin().y()<<","<<p1.getOrigin().z()<< \
"/"<< \
p1.getRotation().x() << "," << p1.getRotation().y()<<","<<p1.getRotation().z()<<","<<p1.getRotation().w()<< \
"]"
Definition at line 26 of file utils.h.
Function Documentation
double getBIC |
( |
double |
loglh, |
|
|
size_t |
k, |
|
|
size_t |
n |
|
) |
| |
std_msgs::ColorRGBA HSV_to_RGB |
( |
double |
h, |
|
|
double |
s, |
|
|
double |
v |
|
) |
| |
std::string uncert_to_string |
( |
double |
sigma_position, |
|
|
double |
sigma_orientation |
|
) |
| |