Go to the documentation of this file.
46 #include <rm_msgs/GimbalCmd.h>
47 #include <rm_msgs/TrackData.h>
48 #include <rm_msgs/GimbalDesError.h>
49 #include <rm_msgs/GimbalPosState.h>
50 #include <rm_gimbal_controllers/GimbalBaseConfig.h>
53 #include <Eigen/Eigen>
56 #include <dynamic_reconfigure/server.h>
58 #include <unordered_map>
74 nh.
param(
"num_data", num_data, 20.0);
76 linear_ = std::make_shared<Vector3WithFilter<double>>(num_data);
77 angular_ = std::make_shared<Vector3WithFilter<double>>(num_data);
84 std::shared_ptr<Vector3WithFilter<double>>
linear_;
85 std::shared_ptr<Vector3WithFilter<double>>
angular_;
86 void update(
double linear_vel[3],
double angular_vel[3],
double period)
101 real_pub_->msg_.linear.x = linear_vel[0];
103 real_pub_->msg_.linear.z = linear_vel[2];
104 real_pub_->msg_.angular.x = angular_vel[0];
105 real_pub_->msg_.angular.y = angular_vel[1];
106 real_pub_->msg_.angular.z = angular_vel[2];
132 hardware_interface::ImuSensorInterface,
133 hardware_interface::EffortJointInterface>
153 void commandCB(
const rm_msgs::GimbalCmdConstPtr& msg);
154 void trackCB(
const rm_msgs::TrackDataConstPtr& msg);
155 void reconfigCB(rm_gimbal_controllers::GimbalBaseConfig& config, uint32_t);
156 std::string
getGimbalFrameID(std::unordered_map<int, urdf::JointConstSharedPtr> joint_urdfs);
157 std::string
getBaseFrameID(std::unordered_map<int, urdf::JointConstSharedPtr> joint_urdfs);
161 std::unordered_map<int, std::unique_ptr<effort_controllers::JointVelocityController>>
ctrls_;
162 std::unordered_map<int, std::unique_ptr<control_toolbox::Pid>>
pid_pos_;
163 std::unordered_map<int, urdf::JointConstSharedPtr>
joint_urdfs_;
171 std::unordered_map<int, std::unique_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalPosState>>>
pos_state_pub_;
172 std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalDesError>>
error_pub_;
200 dynamic_reconfigure::Server<rm_gimbal_controllers::GimbalBaseConfig>*
d_srv_{};
geometry_msgs::TransformStamped odom2gimbal_
bool setDesIntoLimit(const tf2::Quaternion &base2gimbal_des, const urdf::JointConstSharedPtr &joint_urdf, tf2::Quaternion &base2new_des)
void track(const ros::Time &time)
void update(double linear_vel[3], double angular_vel[3], double period)
realtime_tools::RealtimeBuffer< rm_msgs::TrackData > track_rt_buffer_
ros::Subscriber data_track_sub_
void traj(const ros::Time &time)
realtime_tools::RealtimeBuffer< GimbalConfig > config_rt_buffer_
ros::Time last_publish_time_
std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs_
std::unordered_map< int, std::unique_ptr< effort_controllers::JointVelocityController > > ctrls_
std::shared_ptr< ChassisVel > chassis_vel_
dynamic_reconfigure::Server< rm_gimbal_controllers::GimbalBaseConfig > * d_srv_
std::string getBaseFrameID(std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs)
void starting(const ros::Time &time) override
bool enable_gravity_compensation_
void moveJoint(const ros::Time &time, const ros::Duration &period)
void rate(const ros::Time &time, const ros::Duration &period)
std::string gimbal_des_frame_id_
ros::Subscriber cmd_gimbal_sub_
double updateCompensation(double chassis_vel_angular_z)
geometry_msgs::Vector3 mass_origin_
ChassisVel(const ros::NodeHandle &nh)
void trackCB(const rm_msgs::TrackDataConstPtr &msg)
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > filtered_pub_
rm_control::RobotStateHandle robot_state_handle_
geometry_msgs::TransformStamped odom2gimbal_des_
realtime_tools::RealtimeBuffer< rm_msgs::GimbalCmd > cmd_rt_buffer_
std::unordered_map< int, std::unique_ptr< control_toolbox::Pid > > pid_pos_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::GimbalDesError > > error_pub_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
bool dynamic_reconfig_initialized_
hardware_interface::ImuSensorHandle imu_sensor_handle_
std::shared_ptr< BulletSolver > bullet_solver_
geometry_msgs::TransformStamped odom2base_
std::unordered_map< int, bool > pos_des_in_limit_
T param(const std::string ¶m_name, const T &default_val) const
double feedForward(const ros::Time &time)
std::shared_ptr< Vector3WithFilter< double > > linear_
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > real_pub_
rm_msgs::TrackData data_track_
void commandCB(const rm_msgs::GimbalCmdConstPtr &msg)
std::shared_ptr< Vector3WithFilter< double > > angular_
double chassis_compensation_
rm_msgs::GimbalCmd cmd_gimbal_
std::unordered_map< int, std::unique_ptr< realtime_tools::RealtimePublisher< rm_msgs::GimbalPosState > > > pos_state_pub_
geometry_msgs::TransformStamped last_odom2base_
void update(const ros::Time &time, const ros::Duration &period) override
void setDes(const ros::Time &time, double yaw_des, double pitch_des)
std::string getGimbalFrameID(std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs)
void direct(const ros::Time &time)
void reconfigCB(rm_gimbal_controllers::GimbalBaseConfig &config, uint32_t)