Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031 #include <visualization_msgs/MarkerArray.h>
00032
00033 #include <Eigen/Dense>
00034
00035 #include <towr_ros/TowrCommand.h>
00036 #include <towr_ros/topic_names.h>
00037 #include <towr/terrain/height_map.h>
00038
00039
00040 namespace towr {
00041
00042 static ros::Publisher rviz_pub;
00043
00044 void UserCommandCallback(const towr_ros::TowrCommand& msg_in)
00045 {
00046
00047 auto terrain_id = static_cast<HeightMap::TerrainID>(msg_in.terrain);
00048 auto terrain_ = HeightMap::MakeTerrain(terrain_id);
00049
00050
00051 double dxy = 0.06;
00052 double x_min = -1.0;
00053 double x_max = 4.0;
00054 double y_min = -1.0;
00055 double y_max = 1.0;
00056
00057 visualization_msgs::Marker m;
00058 int id = 0;
00059 m.type = visualization_msgs::Marker::CUBE;
00060 m.scale.z = 0.003;
00061 m.ns = "terrain";
00062 m.header.frame_id = "world";
00063 m.color.r = 245./355; m.color.g = 222./355; m.color.b = 179./355;
00064 m.color.a = 0.65;
00065
00066 visualization_msgs::MarkerArray msg;
00067 double x = x_min;
00068 while (x < x_max) {
00069 double y = y_min;
00070 while (y < y_max) {
00071
00072 m.pose.position.x = x;
00073 m.pose.position.y = y;
00074 m.pose.position.z = terrain_->GetHeight(x,y);
00075
00076
00077 Eigen::Vector3d n = terrain_->GetNormalizedBasis(HeightMap::Normal, x, y);
00078 Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d(0,0,1), n);
00079 m.pose.orientation.w = q.w();
00080 m.pose.orientation.x = q.x();
00081 m.pose.orientation.y = q.y();
00082 m.pose.orientation.z = q.z();
00083
00084
00085 double gain = 1.5;
00086 m.scale.x = (1+gain*n.cwiseAbs().x())*dxy;
00087 m.scale.y = (1+gain*n.cwiseAbs().y())*dxy;
00088
00089
00090 m.id = id++;
00091 msg.markers.push_back(m);
00092
00093 y += dxy;
00094 }
00095 x += dxy;
00096 }
00097
00098 rviz_pub.publish(msg);
00099 }
00100
00101 }
00102
00103 int main(int argc, char *argv[])
00104 {
00105 ros::init(argc, argv, "rviz_terrain_visualizer");
00106
00107 ros::NodeHandle n;
00108
00109 ros::Subscriber goal_sub;
00110 goal_sub = n.subscribe(towr_msgs::user_command, 1, towr::UserCommandCallback);
00111 towr::rviz_pub = n.advertise<visualization_msgs::MarkerArray>("xpp/terrain", 1);
00112
00113 ros::spin();
00114
00115 return 1;
00116 }