33 #include <xpp_msgs/TerrainInfo.h> 42 static void StateCallback (
const xpp_msgs::RobotStateCartesian& state_msg)
45 rviz_marker_pub.
publish(rviz_marker_msg);
58 int main(
int argc,
char *argv[])
62 init(argc, argv,
"rviz_marker_visualizer");
69 Subscriber state_sub_curr, state_sub_des, terrain_info_sub;
73 rviz_marker_pub = n.
advertise<visualization_msgs::MarkerArray>(
"xpp/rviz_markers", 1);
void publish(const boost::shared_ptr< M > &message) const
static const std::string robot_state_desired("/xpp/state_des")
int main(int argc, char *argv[])
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void SetTerrainParameters(const xpp_msgs::TerrainInfo &msg)
Additional information that can be used for visualization.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void SetRobotParameters(const xpp_msgs::RobotParameters &msg)
Provides additional robot info that can be used for visualization.
ROSCPP_DECL void spin(Spinner &spinner)
static void ParamsCallback(const xpp_msgs::RobotParameters ¶ms_msg)
static xpp::RvizRobotBuilder robot_builder
static void StateCallback(const xpp_msgs::RobotStateCartesian &state_msg)
static void TerrainInfoCallback(const xpp_msgs::TerrainInfo &terrain_msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
MarkerArray BuildRobotState(const xpp_msgs::RobotStateCartesian &msg) const
Constructs the RVIZ markers from the ROS message.
static ros::Publisher rviz_marker_pub
static const std::string terrain_info("/xpp/terrain_info")
Constructs RVIZ markers that visualize a Cartesian robot state.
static const std::string robot_parameters("/xpp/params")