26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_ 27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_TRAJECTORY_VISUALIZATION_H_ 32 #include <geometry_msgs/Point.h> 34 #include <visualization_msgs/Marker.h> 38 namespace update_filters
56 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
64 const moveit_msgs::MotionPlanRequest &req,
66 moveit_msgs::MoveItErrorCodes& error_code)
override;
79 virtual bool filter(std::size_t start_timestep,
80 std::size_t num_timesteps,
82 const Eigen::MatrixXd& parameters,
83 Eigen::MatrixXd& updates,
84 bool& filtered)
override;
94 virtual void done(
bool success,
int total_iterations,
double final_cost,
const Eigen::MatrixXd& parameters)
override;
97 virtual std::string getName()
const override 99 return name_ +
"/" + group_name_;
103 virtual std::string getGroupName()
const override 115 std::string group_name_;
116 moveit::core::RobotModelConstPtr robot_model_;
117 moveit::core::RobotStatePtr state_;
125 std_msgs::ColorRGBA rgb_;
126 std_msgs::ColorRGBA error_rgb_;
127 bool publish_intermediate_;
128 std::string marker_topic_;
129 std::string marker_namespace_;
132 Eigen::MatrixXd tool_traj_line_;
133 visualization_msgs::Marker tool_traj_marker_;
Publishes rviz markers to visualize the optimized trajectory.
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
see base class for documentation
Interface class which applies filtering methods to the update parameters before it is added onto the ...
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd ¶meters) override
Called by the Stomp at the end of the optimization process.
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
see base class for documentation
virtual bool filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd ¶meters, Eigen::MatrixXd &updates, bool &filtered) override
Publishes rviz markers to visualize the optimized trajectory at each iteration.
This is the base class for all stomp update filters.
virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code) override
see base class for documentation