32 #include <xpp_msgs/RobotStateCartesian.h> 41 int main(
int argc,
char *argv[])
43 ros::init(argc, argv,
"monped_publisher_node");
50 ROS_INFO_STREAM(
"Subscriber to initial state connected");
static xpp_msgs::StateLin3d ToRos(const StateLin3d &xpp)
void publish(const boost::shared_ptr< M > &message) const
StateLin3d & at(EndeffectorID ee)
static const std::string robot_state_desired("/xpp/state_des")
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
EndeffectorsMotion ee_motion_
int main(int argc, char *argv[])
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void spinOnce()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
Endeffectors< Vector3d > ee_forces_
EndeffectorsContact ee_contact_