Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
RVizInterface Class Reference

A class for interfacing between RViz and quad-sdk topics. More...

#include <rviz_interface.h>

Public Member Functions

 RVizInterface (ros::NodeHandle nh)
 Constructor for RVizInterface Class.
 
void spin ()
 Calls ros spinOnce and pubs data at set frequency.
 

Private Member Functions

void robotPlanCallback (const quad_msgs::RobotPlan::ConstPtr &msg, const int pub_id)
 Callback function to handle new body plan data.
 
void grfCallback (const quad_msgs::GRFArray::ConstPtr &msg)
 Callback function to handle new grf data.
 
void discreteBodyPlanCallback (const quad_msgs::RobotPlan::ConstPtr &msg)
 Callback function to handle new body plan discrete state data.
 
void footPlanDiscreteCallback (const quad_msgs::MultiFootPlanDiscrete::ConstPtr &msg)
 Callback function to handle new discrete foot plan data.
 
void footPlanContinuousCallback (const quad_msgs::MultiFootPlanContinuous::ConstPtr &msg)
 Callback function to handle new continous foot plan data.
 
void stateEstimateCallback (const quad_msgs::RobotState::ConstPtr &msg)
 Callback function to handle new state estimate data.
 
void robotStateCallback (const quad_msgs::RobotState::ConstPtr &msg, const int pub_id)
 Callback function to handle new robot state data.
 

Private Attributes

ros::Subscriber global_plan_sub_
 ROS subscriber for the global plan.
 
ros::Subscriber local_plan_sub_
 ROS subscriber for the local plan.
 
ros::Subscriber grf_sub_
 ROS subscriber for the current.
 
ros::Subscriber discrete_body_plan_sub_
 ROS subscriber for the body plan.
 
ros::Subscriber foot_plan_discrete_sub_
 ROS subscriber for the discrete foot plan.
 
ros::Subscriber foot_plan_continuous_sub_
 ROS subscriber for the continuous foot plan.
 
ros::Publisher global_plan_viz_pub_
 ROS Publisher for the interpolated global plan vizualization.
 
ros::Publisher local_plan_viz_pub_
 ROS Publisher for the interpolated local plan vizualization.
 
ros::Publisher current_grf_viz_pub_
 ROS Publisher for the current GRFs.
 
ros::Publisher local_plan_ori_viz_pub_
 ROS Publisher for local plan orientation vizualization.
 
ros::Publisher global_plan_grf_viz_pub_
 ROS Publisher for the interpolated global plan grf vizualization.
 
ros::Publisher local_plan_grf_viz_pub_
 ROS Publisher for the interpolated local plan grf vizualization.
 
ros::Publisher discrete_body_plan_viz_pub_
 ROS Publisher for the discrete body plan vizualization.
 
ros::Publisher foot_plan_discrete_viz_pub_
 ROS Publisher for the footstep plan visualization.
 
ros::Publisher state_estimate_trace_pub_
 ROS Publisher for the state estimate body trace.
 
ros::Publisher ground_truth_state_trace_pub_
 ROS Publisher for the ground truth state body trace.
 
ros::Publisher trajectory_state_trace_pub_
 ROS Publisher for the trajectory state body trace.
 
ros::Publisher foot_0_plan_continuous_viz_pub_
 ROS Publisher for the swing leg 0 visualization.
 
ros::Publisher foot_1_plan_continuous_viz_pub_
 ROS Publisher for the foot 1 plan visualization.
 
ros::Publisher foot_2_plan_continuous_viz_pub_
 ROS Publisher for the foot 2 plan visualization.
 
ros::Publisher foot_3_plan_continuous_viz_pub_
 ROS Publisher for the foot 3 plan visualization.
 
ros::Publisher estimate_joint_states_viz_pub_
 ROS Publisher for the estimated joint states visualization.
 
ros::Publisher ground_truth_joint_states_viz_pub_
 ROS Publisher for the ground truth joint states visualization.
 
ros::Publisher trajectory_joint_states_viz_pub_
 ROS Publisher for the trajectory joint states visualization.
 
ros::Subscriber state_estimate_sub_
 ROS Subscriber for the state estimate.
 
ros::Subscriber ground_truth_state_sub_
 ROS Subscriber for the ground truth state.
 
ros::Subscriber trajectory_state_sub_
 ROS Subscriber for the ground truth state.
 
tf2_ros::TransformBroadcaster estimate_base_tf_br_
 
tf2_ros::TransformBroadcaster ground_truth_base_tf_br_
 
tf2_ros::TransformBroadcaster trajectory_base_tf_br_
 
visualization_msgs::Marker state_estimate_trace_msg_
 Message for state estimate trace.
 
visualization_msgs::Marker ground_truth_state_trace_msg_
 Message for ground truth state trace.
 
visualization_msgs::Marker trajectory_state_trace_msg_
 Message for trajectory state trace.
 
const double trace_reset_threshold_ = 0.2
 Distance threshold for resetting the state traces.
 
ros::NodeHandle nh_
 Nodehandle to pub to and sub from.
 
double update_rate_
 
int orientation_subsample_interval_
 Interval for showing orientation of plan.
 
std::string map_frame_
 Handle for the map frame.
 
std::string tf_prefix_
 Handle multiple robots.
 
std::vector< int > front_left_color_
 Colors.
 
std::vector< int > back_left_color_
 
std::vector< int > front_right_color_
 
std::vector< int > back_right_color_
 
std::vector< int > net_grf_color_
 
std::vector< int > individual_grf_color_
 
const int ESTIMATE = 0
 Publisher IDs.
 
const int GROUND_TRUTH = 1
 
const int TRAJECTORY = 2
 
const int GLOBAL = 0
 
const int LOCAL = 1
 
const int CONNECT = 0
 
const int LEAP_STANCE = 1
 
const int FLIGHT = 2
 
const int LAND_STANCE = 3
 

Detailed Description

A class for interfacing between RViz and quad-sdk topics.

RVizInterface is a container for all of the logic utilized in the template node. The implementation must provide a clean and high level interface to the core algorithm

Constructor & Destructor Documentation

◆ RVizInterface()

RVizInterface::RVizInterface ( ros::NodeHandle  nh)

Constructor for RVizInterface Class.

Parameters
[in]nhROS NodeHandle to publish and subscribe from
Returns
Constructed object of type RVizInterface

Member Function Documentation

◆ discreteBodyPlanCallback()

void RVizInterface::discreteBodyPlanCallback ( const quad_msgs::RobotPlan::ConstPtr &  msg)
private

Callback function to handle new body plan discrete state data.

Parameters
[in]msgplan message contining discrete output of body planner

◆ footPlanContinuousCallback()

void RVizInterface::footPlanContinuousCallback ( const quad_msgs::MultiFootPlanContinuous::ConstPtr &  msg)
private

Callback function to handle new continous foot plan data.

Parameters
[in]SwingLegPlanmessage containing output of swing leg planner

◆ footPlanDiscreteCallback()

void RVizInterface::footPlanDiscreteCallback ( const quad_msgs::MultiFootPlanDiscrete::ConstPtr &  msg)
private

Callback function to handle new discrete foot plan data.

Parameters
[in]Footstepplan message containing output of footstep planner

◆ grfCallback()

void RVizInterface::grfCallback ( const quad_msgs::GRFArray::ConstPtr &  msg)
private

Callback function to handle new grf data.

Parameters
[in]msgplan message contining interpolated output of body planner

Define the endpoint of the GRF arrow

◆ robotPlanCallback()

void RVizInterface::robotPlanCallback ( const quad_msgs::RobotPlan::ConstPtr &  msg,
const int  pub_id 
)
private

Callback function to handle new body plan data.

Parameters
[in]msgplan message contining interpolated output of body planner

Define the endpoint of the GRF arrow

◆ robotStateCallback()

void RVizInterface::robotStateCallback ( const quad_msgs::RobotState::ConstPtr &  msg,
const int  pub_id 
)
private

Callback function to handle new robot state data.

Parameters
[in]msgRobotState message containing output of the state estimator node
[in]pub_idIdentifier of which publisher to use to handle this data

◆ stateEstimateCallback()

void RVizInterface::stateEstimateCallback ( const quad_msgs::RobotState::ConstPtr &  msg)
private

Callback function to handle new state estimate data.

Parameters
[in]msgRobotState message containing output of the state estimator node

Member Data Documentation

◆ estimate_base_tf_br_

tf2_ros::TransformBroadcaster RVizInterface::estimate_base_tf_br_
private

ROS Transform Broadcaster to publish the estimate transform for the base link

◆ ground_truth_base_tf_br_

tf2_ros::TransformBroadcaster RVizInterface::ground_truth_base_tf_br_
private

ROS Transform Broadcaster to publish the ground truth transform for the base link

◆ trajectory_base_tf_br_

tf2_ros::TransformBroadcaster RVizInterface::trajectory_base_tf_br_
private

ROS Transform Broadcaster to publish the trajectory transform for the base link

◆ update_rate_

double RVizInterface::update_rate_
private

Update rate for sending and receiving data, unused since pubs are called in callbacks


The documentation for this class was generated from the following files: