31 #include <visualization_msgs/MarkerArray.h> 33 #include <Eigen/Dense> 35 #include <towr_ros/TowrCommand.h> 57 visualization_msgs::Marker m;
59 m.type = visualization_msgs::Marker::CUBE;
62 m.header.frame_id =
"world";
63 m.color.r = 245./355; m.color.g = 222./355; m.color.b = 179./355;
66 visualization_msgs::MarkerArray msg;
72 m.pose.position.x = x;
73 m.pose.position.y = y;
74 m.pose.position.z = terrain_->GetHeight(x,y);
78 Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d(0,0,1), n);
79 m.pose.orientation.w = q.w();
80 m.pose.orientation.x = q.x();
81 m.pose.orientation.y = q.y();
82 m.pose.orientation.z = q.z();
86 m.scale.x = (1+gain*n.cwiseAbs().x())*dxy;
87 m.scale.y = (1+gain*n.cwiseAbs().y())*dxy;
91 msg.markers.push_back(m);
103 int main(
int argc,
char *argv[])
105 ros::init(argc, argv,
"rviz_terrain_visualizer");
int main(int argc, char *argv[])
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void UserCommandCallback(const towr_ros::TowrCommand &msg_in)
static HeightMap::Ptr MakeTerrain(TerrainID type)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static ros::Publisher rviz_pub
static const std::string user_command("/towr/user_command")