sub_command_=node_->create_subscription<geometry_msgs::msg::Accel>("~/command",1000,
std::bind(&DynamicsLinearizingController::commandCB,this,_1));
- sub_parameters_=node_->create_subscription<std_msgs::msg::Float64MultiArray>("~/dynamics_paremeters",1000,
+ sub_parameters_=node_->create_subscription<std_msgs::msg::Float64MultiArray>("~/dynamics_parameters",1000,
std::bind(&DynamicsLinearizingController::parametersCB,this,_1));
- double wheelBase;
+ double wheelBase;
if(!node_->get_parameter("wheel_separation",wheelBase))
throw std::runtime_error("No 'wheel_separation' parameter.");
throw std::runtime_error("No 'F' parameter.");
F_=Eigen::Map<Eigen::Matrix2d>(FVec.data(),2,2).transpose();
- std::vector<double> GVec;
+ std::vector<double> GVec;
if(!node_->get_parameter("G",GVec))
throw std::runtime_error("No 'G' parameter.");
- Ginv_=Eigen::Map<Eigen::Matrix2d>(GVec.data(),2,2).transpose().inverse();
+ Ginv_=Eigen::Map<Eigen::Matrix2d>(GVec.data(),2,2).transpose().inverse();
time_step_=node_->get_parameter("time_step").as_double();
}
for(unsigned int i=0;i < joints_.size();i++)
phi_[i]=state_interfaces_[i].get_value();
- struct sched_param param;
- param.sched_priority=priority_;
- if(sched_setscheduler(0,SCHED_FIFO,¶m) == -1)
- RCLCPP_WARN(node_->get_logger(),"Failed to set real-time scheduler.");
- if(mlockall(MCL_CURRENT|MCL_FUTURE) == -1)
- RCLCPP_WARN(node_->get_logger(),"Failed to lock memory.");
+ struct sched_param param;
+ param.sched_priority=priority_;
+ if(sched_setscheduler(0,SCHED_FIFO,¶m) == -1)
+ RCLCPP_WARN(node_->get_logger(),"Failed to set real-time scheduler.");
+ if(mlockall(MCL_CURRENT|MCL_FUTURE) == -1)
+ RCLCPP_WARN(node_->get_logger(),"Failed to lock memory.");
return CallbackReturn::SUCCESS;
}
}
}
- // Linearization
- Eigen::Vector2d uf(u[0]*u[1],sqr(u[1]));
- auto torque=Ginv_*(v_-F_*uf);
+ // Linearization
+ Eigen::Vector2d uf(u[0]*u[1],sqr(u[1]));
+ auto torque=Ginv_*(v_-F_*uf);
// Apply torques
for(unsigned int i=0;i < joints_.size();i++)
command_interfaces_[i].set_value(torque[i]);
- if(rt_status_publisher_ && rt_status_publisher_->trylock())
- {
+ if(rt_status_publisher_ && rt_status_publisher_->trylock())
+ {
rt_status_publisher_->msg_.header.stamp=time;
rt_status_publisher_->msg_.set_point.linear.x=v_[0];
rt_status_publisher_->msg_.command[i]=torque[i];
rt_status_publisher_->unlockAndPublish();
- }
+ }
- Eigen::Vector3d x;
+ Eigen::Vector3d x;
odom_.getPose(x);
- if(rt_odom_publisher_ && rt_odom_publisher_->trylock())
- {
+ if(rt_odom_publisher_ && rt_odom_publisher_->trylock())
+ {
rt_odom_publisher_->msg_.header.stamp=time;
rt_odom_publisher_->msg_.pose.pose.position.x=x[0];
rt_odom_publisher_->msg_.twist.twist.angular.z=u[1];
rt_odom_publisher_->unlockAndPublish();
- }
+ }
- if(rt_tf_odom_publisher_ && rt_tf_odom_publisher_->trylock())
- {
+ if(rt_tf_odom_publisher_ && rt_tf_odom_publisher_->trylock())
+ {
geometry_msgs::msg::TransformStamped &odom_frame=
rt_tf_odom_publisher_->msg_.transforms[0];
odom_frame.header.stamp=time;
odom_frame.transform.rotation.w=cos(x[2]/2);
rt_tf_odom_publisher_->unlockAndPublish();
- }
+ }
return controller_interface::return_type::OK;
}