Go to the documentation of this file.
33 #include <xpp_msgs/TerrainInfo.h>
42 static void StateCallback (
const xpp_msgs::RobotStateCartesian& state_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;
Constructs RVIZ markers that visualize a Cartesian robot state.
static const std::string terrain_info("/xpp/terrain_info")
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void SetTerrainParameters(const xpp_msgs::TerrainInfo &msg)
Additional information that can be used for visualization.
int main(int argc, char *argv[])
void SetRobotParameters(const xpp_msgs::RobotParameters &msg)
Provides additional robot info that can be used for visualization.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
MarkerArray BuildRobotState(const xpp_msgs::RobotStateCartesian &msg) const
Constructs the RVIZ markers from the ROS message.
static void ParamsCallback(const xpp_msgs::RobotParameters ¶ms_msg)
static xpp::RvizRobotBuilder robot_builder
static void StateCallback(const xpp_msgs::RobotStateCartesian &state_msg)
static const std::string robot_state_desired("/xpp/state_des")
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
static void TerrainInfoCallback(const xpp_msgs::TerrainInfo &terrain_msg)
static const std::string robot_parameters("/xpp/params")
static ros::Publisher rviz_marker_pub
xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:16