40 #include <Eigen/Eigenvalues> 45 #include <moveit_msgs/ChangeDriftDimensions.h> 46 #include <moveit_msgs/ChangeControlDimensions.h> 48 #include <sensor_msgs/Joy.h> 49 #include <std_msgs/Float64MultiArray.h> 63 void jointsCB(
const sensor_msgs::JointStateConstPtr& msg);
74 moveit_msgs::ChangeDriftDimensions::Response&
res);
79 moveit_msgs::ChangeControlDimensions::Response& res);
std::unique_ptr< CollisionCheckThread > collision_checker_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool startCollisionCheckThread()
Start collision checking.
std::unique_ptr< std::thread > jog_calc_thread_
std::unique_ptr< std::thread > collision_check_thread_
std::unique_ptr< JogCalcs > jog_calcs_
JogArmShared shared_variables_
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
bool stopCollisionCheckThread()
Stop collision checking.
bool stopJogCalcThread()
Stop the main calculation thread.
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Start the main calculation thread.
bool startJogCalcThread()
bool readParameters(ros::NodeHandle &n)
void jointsCB(const sensor_msgs::JointStateConstPtr &msg)
Update the joints of the robot.
JogArmParameters ros_parameters_